debug urdf
This commit is contained in:
parent
145bf17cb7
commit
acf67fbc0d
|
|
@ -21,9 +21,9 @@ SimpleController::SimpleController(const ros::NodeHandle &nh,
|
||||||
ROS_INFO_STREAM("Using wheel separation " << separation);
|
ROS_INFO_STREAM("Using wheel separation " << separation);
|
||||||
right_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_right_controller/command", 10);
|
right_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_right_controller/command", 10);
|
||||||
left_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_left_controller/command", 10);
|
left_cmd_pub_ = nh_.advertise<std_msgs::Float64>("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);
|
joint_sub_ = nh_.subscribe("joint_states", 1000, &SimpleController::jointCallback, this);
|
||||||
odom_pub_ = nh_.advertise<nav_msgs::Odometry>("kubot_description/odom", 10);
|
odom_pub_ = nh_.advertise<nav_msgs::Odometry>("turtlebot_controller/odom", 10);
|
||||||
|
|
||||||
speed_conversion_ << radius/2, radius/2, radius/separation, -radius/separation;
|
speed_conversion_ << radius/2, radius/2, radius/separation, -radius/separation;
|
||||||
ROS_INFO_STREAM("The conversion matrix is \n" << speed_conversion_);
|
ROS_INFO_STREAM("The conversion matrix is \n" << speed_conversion_);
|
||||||
|
|
|
||||||
|
|
@ -89,7 +89,24 @@
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="caster_back_right_link">
|
<link name="caster_link">
|
||||||
|
<collision>
|
||||||
|
<origin xyz="0 0.001 0" rpy="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<box size="0.030 0.009 0.020"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
|
||||||
|
<inertial>
|
||||||
|
<origin xyz="0 0 0" />
|
||||||
|
<mass value="0.005" />
|
||||||
|
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
|
||||||
|
iyy="0.001" iyz="0.0"
|
||||||
|
izz="0.001" />
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
|
||||||
|
<!-- <link name="caster_back_right_link">
|
||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0.001 0" rpy="0 0 0"/>
|
<origin xyz="0 0.001 0" rpy="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
|
|
@ -121,7 +138,7 @@
|
||||||
iyy="0.001" iyz="0.0"
|
iyy="0.001" iyz="0.0"
|
||||||
izz="0.001" />
|
izz="0.001" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link> -->
|
||||||
|
|
||||||
<link name="imu_link"/>
|
<link name="imu_link"/>
|
||||||
|
|
||||||
|
|
@ -149,7 +166,7 @@
|
||||||
izz="0.001" />
|
izz="0.001" />
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
<!--
|
||||||
<link name="camera_link">
|
<link name="camera_link">
|
||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0.005 0.011 0.013" rpy="0 0 0"/>
|
<origin xyz="0.005 0.011 0.013" rpy="0 0 0"/>
|
||||||
|
|
@ -157,11 +174,11 @@
|
||||||
<box size="0.015 0.030 0.027"/>
|
<box size="0.015 0.030 0.027"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link> -->
|
||||||
|
|
||||||
<link name="camera_rgb_frame"/>
|
<!-- <link name="camera_rgb_frame"/> -->
|
||||||
|
|
||||||
<link name="camera_rgb_optical_frame"/>
|
<!-- <link name="camera_rgb_optical_frame"/> -->
|
||||||
|
|
||||||
<joint name="base_joint" type="fixed">
|
<joint name="base_joint" type="fixed">
|
||||||
<parent link="base_footprint"/>
|
<parent link="base_footprint"/>
|
||||||
|
|
@ -182,7 +199,7 @@
|
||||||
<origin xyz="0.0 -0.144 0.023" rpy="-1.57 0 0"/>
|
<origin xyz="0.0 -0.144 0.023" rpy="-1.57 0 0"/>
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
<!--
|
||||||
<joint name="caster_back_right_joint" type="fixed">
|
<joint name="caster_back_right_joint" type="fixed">
|
||||||
<parent link="base_link"/>
|
<parent link="base_link"/>
|
||||||
<child link="caster_back_right_link"/>
|
<child link="caster_back_right_link"/>
|
||||||
|
|
@ -193,6 +210,12 @@
|
||||||
<parent link="base_link"/>
|
<parent link="base_link"/>
|
||||||
<child link="caster_back_left_link"/>
|
<child link="caster_back_left_link"/>
|
||||||
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
|
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
|
||||||
|
</joint> -->
|
||||||
|
|
||||||
|
<joint name="caster__joint" type="fixed">
|
||||||
|
<parent link="base_link"/>
|
||||||
|
<child link="caster_link"/>
|
||||||
|
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="imu_joint" type="fixed">
|
<joint name="imu_joint" type="fixed">
|
||||||
|
|
@ -207,22 +230,22 @@
|
||||||
<origin xyz="-0.024 0 0.122" rpy="0 0 0"/>
|
<origin xyz="-0.024 0 0.122" rpy="0 0 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="camera_joint" type="fixed">
|
<!-- <joint name="camera_joint" type="fixed">
|
||||||
<origin xyz="0.073 -0.011 0.084" rpy="0 0 0"/>
|
<origin xyz="0.073 -0.011 0.084" rpy="0 0 0"/>
|
||||||
<parent link="base_link"/>
|
<parent link="base_link"/>
|
||||||
<child link="camera_link"/>
|
<child link="camera_link"/>
|
||||||
</joint>
|
</joint> -->
|
||||||
|
<!--
|
||||||
<joint name="camera_rgb_joint" type="fixed">
|
<joint name="camera_rgb_joint" type="fixed">
|
||||||
<origin xyz="0.003 0.011 0.009" rpy="0 0 0"/>
|
<origin xyz="0.003 0.011 0.009" rpy="0 0 0"/>
|
||||||
<parent link="camera_link"/>
|
<parent link="camera_link"/>
|
||||||
<child link="camera_rgb_frame"/>
|
<child link="camera_rgb_frame"/>
|
||||||
</joint>
|
</joint> -->
|
||||||
|
|
||||||
<joint name="camera_rgb_optical_joint" type="fixed">
|
<!-- <joint name="camera_rgb_optical_joint" type="fixed">
|
||||||
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
|
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
|
||||||
<parent link="camera_rgb_frame"/>
|
<parent link="camera_rgb_frame"/>
|
||||||
<child link="camera_rgb_optical_frame"/>
|
<child link="camera_rgb_optical_frame"/>
|
||||||
</joint>
|
</joint> -->
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
Loading…
Reference in New Issue