From acf67fbc0daa8e1100344522b7d5bbd2f89cccea Mon Sep 17 00:00:00 2001 From: "ly.pechvattana" Date: Tue, 29 Aug 2023 23:23:45 -0700 Subject: [PATCH] debug urdf --- .../src/simple_controller.cpp | 4 +- .../urdf/turtlebot.urdf.xacro | 49 ++++++++++++++----- 2 files changed, 38 insertions(+), 15 deletions(-) diff --git a/src/turtlebot_controller/src/simple_controller.cpp b/src/turtlebot_controller/src/simple_controller.cpp index 7066c28..8681c91 100644 --- a/src/turtlebot_controller/src/simple_controller.cpp +++ b/src/turtlebot_controller/src/simple_controller.cpp @@ -21,9 +21,9 @@ SimpleController::SimpleController(const ros::NodeHandle &nh, ROS_INFO_STREAM("Using wheel separation " << separation); right_cmd_pub_ = nh_.advertise("wheel_right_controller/command", 10); left_cmd_pub_ = nh_.advertise("wheel_left_controller/command", 10); - vel_sub_ = nh_.subscribe("kubot_description/cmd_vel", 1000, &SimpleController::velCallback, this); + vel_sub_ = nh_.subscribe("turtlebot_controller/cmd_vel", 1000, &SimpleController::velCallback, this); joint_sub_ = nh_.subscribe("joint_states", 1000, &SimpleController::jointCallback, this); - odom_pub_ = nh_.advertise("kubot_description/odom", 10); + odom_pub_ = nh_.advertise("turtlebot_controller/odom", 10); speed_conversion_ << radius/2, radius/2, radius/separation, -radius/separation; ROS_INFO_STREAM("The conversion matrix is \n" << speed_conversion_); diff --git a/src/turtlebot_description/urdf/turtlebot.urdf.xacro b/src/turtlebot_description/urdf/turtlebot.urdf.xacro index 7a52a97..6e2de4d 100644 --- a/src/turtlebot_description/urdf/turtlebot.urdf.xacro +++ b/src/turtlebot_description/urdf/turtlebot.urdf.xacro @@ -89,7 +89,24 @@ - + + + + + + + + + + + + + + + + @@ -149,7 +166,7 @@ izz="0.001" /> - + - + - + @@ -182,7 +199,7 @@ - + + + + + + @@ -207,22 +230,22 @@ - + + - + \ No newline at end of file