Skip to content

Commit b194f4d

Browse files
committed
change control
1 parent 51b43cd commit b194f4d

1 file changed

Lines changed: 12 additions & 9 deletions

File tree

src/modelec_com/src/pcb_odo_interface.cpp

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -73,19 +73,22 @@ namespace Modelec
7373
"joy", 30,
7474
[this](const sensor_msgs::msg::Joy::SharedPtr msg)
7575
{
76-
double forward = msg->axes[1];
77-
double turn = msg->axes[2];
76+
double left_axis = msg->axes[1];
77+
double right_axis = msg->axes[2];
7878

79-
if (fabs(forward) < 0.05) forward = 0.0;
80-
if (fabs(turn) < 0.05) turn = 0.0;
79+
if (fabs(left_axis) < 0.05) left_axis = 0.0;
80+
if (fabs(right_axis) < 0.05) right_axis = 0.0;
8181

82-
int left = static_cast<int>(forward * 626 - turn * 626);
83-
int right = static_cast<int>(forward * 626 + turn * 626);
82+
// int left = static_cast<int>(forward * 626 - turn * 626);
83+
// int right = static_cast<int>(forward * 626 + turn * 626);
8484

85-
left = std::max(-626, std::min(626, left));
86-
right = std::max(-626, std::min(626, right));
85+
int left_motor = static_cast<int>(left_axis * 626);
86+
int right_motor = static_cast<int>(right_axis * 626);
8787

88-
SetMotor(left, right);
88+
left_motor = std::max(-626, std::min(626, left_motor));
89+
right_motor = std::max(-626, std::min(626, right_motor));
90+
91+
SetMotor(left_motor, right_motor);
8992
});
9093

9194
start_odo_sub_ = this->create_subscription<std_msgs::msg::Bool>(

0 commit comments

Comments
 (0)