Problem Moving the Robot in Rviz
I have written a urdf file for my differential drive mobile robot an want to make it move on rviz. I'm doing the tutorials on the book "Learning ROS for Robotic Programming" and used the codes and examples there, modifying them for myself.
So here is the urdf code;
<robot name="AGV">
<link name="base_link">
<visual>
<geometry>
<box size="0.49 .82 .2"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
<material name="gray">
<color rgba="0 0 0 0.6"/>
</material>
</visual>
</link>
<link name="wheel_1">
<visual>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<origin rpy="0 1.57079633 0" xyz="0.22 0 0"/>
<material name="black">
<color rgba="1 0 0 1"/>
</material>
</visual>
</link>
<link name="wheel_2">
<visual>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
<origin rpy="0 1.57079633 0" xyz="-0.22 0 0"/>
<material name="black"/>
</visual>
</link>
<joint name="base_to_wheel1" type="continuous">
<parent link="base_link"/>
<child link="wheel_1"/>
<origin xyz="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="base_to_wheel2" type="continuous">
<parent link="base_link"/>
<child link="wheel_2"/>
<origin xyz="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
</robot>
This is the broadcaster code:
#include<string>
#include<ros/ros.h>
#include<tf/transform_broadcaster.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "tf_broadcaster");
ros::NodeHandle n;
tf::TransformBroadcaster broadcaster;
ros::Rate loop_rate(30);
double angle= 0;
// message declarations
geometry_msgs::TransformStamped odom_trans;
odom_trans.header.frame_id = "odom";
odom_trans.child_frame_id = "base_link";
while (ros::ok()) {
// (moving in a circle with radius 1)
odom_trans.header.stamp = ros::Time::now();
odom_trans.transform.translation.x = cos(angle);
odom_trans.transform.translation.y = sin(angle);
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(angle);
//send transform
broadcaster.sendTransform(odom_trans);
loop_rate.sleep();
}
return 0;
}
I launch the urdf on rviz and the node, but I get the problem as; No transform from [wheel_1] to [/base_link] No transform from [wheel_2] to [/base_link]
I'm not very experienced on ROS and TF and couldn't figure out why there is no transform between two links, isn't urdf is for that?