Skip to content

Commit

Permalink
replace Twist with TwistStamped (#249)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jan 2, 2024
1 parent b39074a commit 6bf5f06
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ diff_drive_base_controller:

cmd_vel_timeout: 0.5
#publish_limited_velocity: true
use_stamped_vel: false
use_stamped_vel: true
#velocity_rolling_window_size: 10

# Velocity and acceleration limits
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ tricycle_controller:

# cmd_vel input
cmd_vel_timeout: 500 # In milliseconds. Timeout to stop if no cmd_vel is received
use_stamped_vel: false # Set to True if using TwistStamped.
use_stamped_vel: true # Set to True if using TwistStamped.

# Debug
publish_ackermann_command: true # Publishes AckermannDrive. The speed does not comply to the msg definition, it the wheel angular speed in rad/s.
22 changes: 12 additions & 10 deletions gazebo_ros2_control_demos/examples/example_diff_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>

using namespace std::chrono_literals;

Expand All @@ -27,20 +27,22 @@ int main(int argc, char * argv[])
std::shared_ptr<rclcpp::Node> node =
std::make_shared<rclcpp::Node>("diff_drive_test_node");

auto publisher = node->create_publisher<geometry_msgs::msg::Twist>(
"/diff_drive_base_controller/cmd_vel_unstamped", 10);
auto publisher = node->create_publisher<geometry_msgs::msg::TwistStamped>(
"/tricycle_controller/cmd_vel", 10);

RCLCPP_INFO(node->get_logger(), "node created");

geometry_msgs::msg::Twist command;
geometry_msgs::msg::TwistStamped command;

command.linear.x = 0.2;
command.linear.y = 0.0;
command.linear.z = 0.0;
command.header.stamp = node->now();

command.angular.x = 0.0;
command.angular.y = 0.0;
command.angular.z = 0.1;
command.twist.linear.x = 0.2;
command.twist.linear.y = 0.0;
command.twist.linear.z = 0.0;

command.twist.angular.x = 0.0;
command.twist.angular.y = 0.0;
command.twist.angular.z = 0.1;

while (1) {
publisher->publish(command);
Expand Down
20 changes: 11 additions & 9 deletions gazebo_ros2_control_demos/examples/example_tricycle_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>

using namespace std::chrono_literals;

Expand All @@ -27,20 +27,22 @@ int main(int argc, char * argv[])
std::shared_ptr<rclcpp::Node> node =
std::make_shared<rclcpp::Node>("tricycle_drive_test_node");

auto publisher = node->create_publisher<geometry_msgs::msg::Twist>(
auto publisher = node->create_publisher<geometry_msgs::msg::TwistStamped>(
"/tricycle_controller/cmd_vel", 10);

RCLCPP_INFO(node->get_logger(), "node created");

geometry_msgs::msg::Twist command;
geometry_msgs::msg::TwistStamped command;

command.linear.x = 0.2;
command.linear.y = 0.0;
command.linear.z = 0.0;
command.header.stamp = node->now();

command.angular.x = 0.0;
command.angular.y = 0.0;
command.angular.z = 0.1;
command.twist.linear.x = 0.2;
command.twist.linear.y = 0.0;
command.twist.linear.z = 0.0;

command.twist.angular.x = 0.0;
command.twist.angular.y = 0.0;
command.twist.angular.z = 0.1;

while (1) {
publisher->publish(command);
Expand Down

0 comments on commit 6bf5f06

Please sign in to comment.