Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add inverted reverse param #35

Merged
merged 3 commits into from
Jun 7, 2023
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 6 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ The package comes with the `teleop_node` that republishes `sensor_msgs/msg/Joy`

- `enable_button (int, default: 0)`
- Joystick button to enable regular-speed movement.

- `enable_turbo_button (int, default: -1)`
- Joystick button to enable high-speed movement (disabled when -1).

Expand All @@ -51,21 +51,22 @@ The package comes with the `teleop_node` that republishes `sensor_msgs/msg/Joy`
- `axis_angular.yaw (int, default: 2)`
- `axis_angular.pitch (int, default: -1)`
- `axis_angular.roll (int, default: -1)`

- `scale_angular.<axis>`
- Scale to apply to joystick angular axis.
- `scale_angular.yaw (double, default: 0.5)`
- `scale_angular.pitch (double, default: 0.0)`
- `scale_angular.roll (double, default: 0.0)`

- `scale_angular_turbo.<axis>`
- Scale to apply to joystick angular axis for high-speed movement.
- `scale_angular_turbo.yaw (double, default: 1.0)`
- `scale_angular_turbo.pitch (double, default: 0.0)`
- `scale_angular_turbo.roll (double, default: 0.0)`



- `inverted_reverse (bool, default: false)`
- Whether to invert turning left-rigth while reversing (useful for differential wheeled robots).
clalancette marked this conversation as resolved.
Show resolved Hide resolved



# Usage
Expand Down
16 changes: 14 additions & 2 deletions src/teleop_twist_joy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ struct TeleopTwistJoy::Impl
int64_t enable_button;
int64_t enable_turbo_button;

bool inverted_reverse;

std::map<std::string, int64_t> axis_linear_map;
std::map<std::string, std::map<std::string, double>> scale_linear_map;

Expand Down Expand Up @@ -89,6 +91,8 @@ TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions & options)

pimpl_->enable_turbo_button = this->declare_parameter("enable_turbo_button", -1);

pimpl_->inverted_reverse = this->declare_parameter("inverted_reverse", false);

std::map<std::string, int64_t> default_linear_map{
{"x", 5L},
{"y", -1L},
Expand Down Expand Up @@ -143,6 +147,9 @@ TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions & options)
ROS_INFO_COND_NAMED(
pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
"Turbo on button %" PRId64 ".", pimpl_->enable_turbo_button);
ROS_INFO_COND_NAMED(
1, "TeleopTwistJoy",
"Teleop enable inverted reverse %d.", pimpl_->inverted_reverse);
clalancette marked this conversation as resolved.
Show resolved Hide resolved

for (std::map<std::string, int64_t>::iterator it = pimpl_->axis_linear_map.begin();
it != pimpl_->axis_linear_map.end(); ++it)
Expand Down Expand Up @@ -180,6 +187,8 @@ TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions & options)
for (const auto & parameter : parameters) {
if (parameter.get_name() == "require_enable_button") {
this->pimpl_->require_enable_button = parameter.get_value<rclcpp::PARAMETER_BOOL>();
} else if (parameter.get_name() == "inverted_reverse") {
this->pimpl_->inverted_reverse = parameter.get_value<rclcpp::PARAMETER_BOOL>();
} else if (parameter.get_name() == "enable_button") {
this->pimpl_->enable_button = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "enable_turbo_button") {
Expand Down Expand Up @@ -268,10 +277,13 @@ void TeleopTwistJoy::Impl::sendCmdVelMsg(
// Initializes with zeros by default.
auto cmd_vel_msg = std::make_unique<geometry_msgs::msg::Twist>();

cmd_vel_msg->linear.x = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "x");
double lin_x = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "x");
double ang_z = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "yaw");

cmd_vel_msg->linear.x = lin_x;
cmd_vel_msg->linear.y = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "y");
cmd_vel_msg->linear.z = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "z");
cmd_vel_msg->angular.z = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "yaw");
cmd_vel_msg->angular.z = (lin_x < 0.0 && inverted_reverse) ? -ang_z : ang_z;
cmd_vel_msg->angular.y = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "pitch");
cmd_vel_msg->angular.x = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "roll");

Expand Down