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

Replace Twist with TwistStamped #210

Merged
merged 1 commit into from
Jan 2, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,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 @@ -50,7 +50,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 gz_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>(
"/diff_drive_base_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.1;
command.linear.y = 0.0;
command.linear.z = 0.0;
command.header.stamp = node->now();

command.angular.x = 0.1;
command.angular.y = 0.0;
command.angular.z = 0.0;
command.twist.linear.x = 0.1;
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 gz_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
Loading