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

Fix ackermann demo #468

Merged
merged 4 commits into from
Jan 2, 2025
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 @@ -20,6 +20,7 @@ ackermann_steering_controller:
reference_timeout: 2.0
rear_wheels_names: ['rear_left_wheel_joint', 'rear_right_wheel_joint']
front_wheels_names: ['left_wheel_steering_joint', 'right_wheel_steering_joint']
use_stamped_vel: true
open_loop: false
velocity_rolling_window_size: 10
base_frame_id: base_link
Expand Down
32 changes: 20 additions & 12 deletions ign_ros2_control_demos/examples/example_ackermann_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,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 @@ -28,25 +28,33 @@ int main(int argc, char * argv[])
std::shared_ptr<rclcpp::Node> node =
std::make_shared<rclcpp::Node>("ackermann_drive_test_node");

auto publisher = node->create_publisher<geometry_msgs::msg::Twist>(
"/ackermann_steering_controller/reference_unstamped", 10);
node->set_parameter(rclcpp::Parameter("use_sim_time", true));

auto publisher = node->create_publisher<geometry_msgs::msg::TwistStamped>(
"/ackermann_steering_controller/reference", 10);

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

geometry_msgs::msg::Twist command;
geometry_msgs::msg::Twist tw;

tw.linear.x = 0.5;
tw.linear.y = 0.0;
tw.linear.z = 0.0;

command.linear.x = 0.5;
command.linear.y = 0.0;
command.linear.z = 0.0;
tw.angular.x = 0.0;
tw.angular.y = 0.0;
tw.angular.z = 0.3;

command.angular.x = 0.0;
command.angular.y = 0.0;
command.angular.z = 0.3;
geometry_msgs::msg::TwistStamped command;
command.twist = tw;

while (1) {
publisher->publish(command);
std::this_thread::sleep_for(50ms);
rclcpp::spin_some(node);
if (node->get_clock()->started()) {
command.header.stamp = node->now();
publisher->publish(command);
}
std::this_thread::sleep_for(50ms);
}
rclcpp::shutdown();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,6 @@ def generate_launch_description():
on_exit=[load_ackermann_controller],
)
),
bridge,
node_robot_state_publisher,
gz_spawn_entity,
# Launch Arguments
Expand Down
30 changes: 16 additions & 14 deletions ign_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia ixx="0.126164" ixy="0.0" ixz="0.0" iyy="0.416519" iyz="0.0" izz="0.481014" />
<mass value="100" />
<inertia ixx="10.4" ixy="0.0" ixz="0.0" iyy="35.4" iyz="0.0" izz="41.66" />
</inertial>
</link>

Expand All @@ -60,8 +60,8 @@
</visual>

<inertial>
<mass value="2" />
<inertia ixx="0.145833" ixy="0.0" ixz="0.0" iyy="0.145833" iyz="0.0" izz="0.125" />
<mass value="11.3" />
<inertia ixx="0.26" ixy="0.0" ixz="0.0" iyy="0.26" iyz="0.0" izz="0.51" />
</inertial>
</link>

Expand All @@ -87,8 +87,8 @@
<material name="Black" />
</visual>
<inertial>
<mass value="2" />
<inertia ixx="0.145833" ixy="0.0" ixz="0.0" iyy="0.145833" iyz="0.0" izz="0.125" />
<mass value="11.3" />
<inertia ixx="0.26" ixy="0.0" ixz="0.0" iyy="0.26" iyz="0.0" izz="0.51" />
</inertial>
</link>

Expand All @@ -108,12 +108,13 @@
</inertial>
</link>

<joint name="left_wheel_steering_joint" type="continuous">
<origin xyz="0.9 0.5 -0.2" rpy="-1.57 0 0" />
<joint name="left_wheel_steering_joint" type="revolute">
<origin xyz="0.9 -0.5 -0.2" rpy="1.57 0 0" />
<parent link="chassis" />
<child link="left_wheel_steering" />
<axis xyz="0 1 0" />
<dynamics damping="0.2" />
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/>
</joint>

<!-- right steer Link -->
Expand All @@ -124,12 +125,13 @@
</inertial>
</link>

<joint name="right_wheel_steering_joint" type="continuous">
<origin xyz="0.9 -0.5 -0.2" rpy="-1.57 0 0" />
<joint name="right_wheel_steering_joint" type="revolute">
<origin xyz="0.9 0.5 -0.2" rpy="1.57 0 0" />
<parent link="chassis" />
<child link="right_wheel_steering" />
<axis xyz="0 1 0" />
<dynamics damping="0.2" />
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/>
</joint>

<!-- front left wheel Link -->
Expand All @@ -146,8 +148,8 @@
<material name="Black" />
</visual>
<inertial>
<mass value="2" />
<inertia ixx="0.145833" ixy="0.0" ixz="0.0" iyy="0.145833" iyz="0.0" izz="0.125" />
<mass value="11.3" />
<inertia ixx="0.26" ixy="0.0" ixz="0.0" iyy="0.26" iyz="0.0" izz="0.51" />
</inertial>
</link>

Expand All @@ -173,8 +175,8 @@
<material name="Black" />
</visual>
<inertial>
<mass value="2" />
<inertia ixx="0.145833" ixy="0.0" ixz="0.0" iyy="0.145833" iyz="0.0" izz="0.125" />
<mass value="11.3" />
<inertia ixx="0.26" ixy="0.0" ixz="0.0" iyy="0.26" iyz="0.0" izz="0.51" />
</inertial>
</link>

Expand Down
Loading