ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

p3dx urdf model isn't shown correctly in rviz

asked 2011-08-15 19:58:53 -0500

jan gravatar image

updated 2011-08-21 20:35:36 -0500

Hi all,

I am reffering to the question below:

pioneer 3dx simulation using rviz and stage

My problem is the same as described in the other question but the answers did not help me solving it. I am not using amcl because I use the gmapping for the navigation stack to run. Is there a possibility to get those wheels at the right position without using amcl?

I think my big problem is that I am not good at the whole transform and urdf thing. Where can I adjust some things in the model or add for example a kinect to the top of the bot or a laserscanner. In the end I would like to have a complete simulation of my real robot. (I am using a pioneer 3dx with a SICK LMS 200 and a Katana 300 manipulation arm)

EDIT:

Here you can see my TF-tree. The wheels are missing. I think they have an other specification than the other elements of the robot. Where can i change this spec?

tf-frames.pdf

This is the urdf-model publisher.cc file. Why are there only 4 joints? Is this a problem? How can I add something?

#include <ros/ros.h>
#include <sensor_msgs/JointState.h>

int main( int argc, char* argv[] )
{
  ros::init(argc, argv, "p2os_publisher" );
  ros::NodeHandle n;

  ros::Publisher joint_state_publisher = n.advertise<sensor_msgs::JointState>("joint_states",1000);
  ros::Rate loop_rate(15);
  sensor_msgs::JointState js;

    js.name.push_back(std::string("base_swivel_joint"));
    js.position.push_back(0);
    js.name.push_back(std::string("swivel_hubcap_joint"));
    js.position.push_back(0);
    js.name.push_back(std::string("base_left_hubcap_joint"));
    js.position.push_back(0);
    js.name.push_back(std::string("base_right_hubcap_joint"));
    js.position.push_back(0);

    while( n.ok() )
    {
    js.header.frame_id="/base_link";
    js.header.stamp = ros::Time::now();
        joint_state_publisher.publish(js);
        ros::spinOnce();
        loop_rate.sleep();
    }
}

This is the launch file (pioneer3dx_urdf.launch):

<launch>
    <include file="$(find p2os_urdf)/launch/upload_pioneer3dx.xml"/>
  <node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher">
    <remap from="joint_state" to="joint_state"/>
    <param name="publish_frequency" type="double" value="15.0"/>
    <param name="tf_prefix" type="string" value=""/>
  </node>
    <node pkg="p2os_urdf" type="publisher" name="publisher"/>
</launch>

What else do you need?

I am just wondering that I cant find some URDF-specifications in this stack only .xacro-files?! Do you wish to see these files too? Thats a lot of code...

edit retag flag offensive close merge delete

Comments

Maybe something with your TF tree is wrong. Can you please post the output of `rosrun tf tf_monitor`?
Lorenz gravatar image Lorenz  ( 2011-08-20 02:04:46 -0500 )edit
Yeah that might be possible but I dont know where to start in all these files. I will post a picture of the tf-tree soon.
jan gravatar image jan  ( 2011-08-21 18:52:49 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2011-08-19 23:08:36 -0500

updated 2011-08-23 21:02:02 -0500

We are running a similar setup, and at the moment actively developing ROS integration for the Katana arm. The arm we use is the Katana 450, so in order to use the Katana 300 you will have to modify some things. Anyway, the katana_driver stack could be a good place to start.

Could you post your URDF files, so we can have a look at it?

Edit: Thanks for posting the files. They are the unchanged files from p2os_urdf, so I did the following:

svn co https://usc-ros-pkg.svn.sourceforge.net/svnroot/usc-ros-pkg/trunk/p2os
cd p2os/
rosmake
roslaunch p2os_urdf/launch/pioneer3dx_urdf.launch
rosrun rviz rviz

For me, the model looks perfectly alright. Did you make sure to click on "global frame" in RViz and select some existing frame (e.g., base_link)?

Judging from your TF tree, you seem to have other stuff running, too (like the openni_kinect drivers).

You should probably spend some time doing the URDF tutorials, they are really good. This should also answer your question why there are only .xacro files and no .urdf files.

After doing that, you can have a look at the turtlebot_description package to see how they added a Kinect to the robot.

edit flag offensive delete link more

Comments

I posted the files above. Do you need the .xacro files too?
jan gravatar image jan  ( 2011-08-23 19:06:47 -0500 )edit
Thank you for your fast response. I did the same like you and it worked. I don't know why but a new checkout made it :D. Now my last question is how to combine e.g. the Katana model with the pioneer base? I did the tutorials but I have problems with the robot_state_publisher if I start both models..
jan gravatar image jan  ( 2011-08-23 21:43:34 -0500 )edit
I will try the turtle bot thing first. I overread that. Sorry.
jan gravatar image jan  ( 2011-08-23 21:46:15 -0500 )edit
To combine the models, you should write a xacro file that includes both models, and then add a fixed joint between some link in model 1 (e.g., base_link) and the root link in model 2.
Martin Günther gravatar image Martin Günther  ( 2011-08-23 22:50:41 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-08-15 19:58:53 -0500

Seen: 1,980 times

Last updated: Aug 23 '11