Re: [ros-users] Issues Communicating with Rviz

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
Delete this message
Reply to this message
Author: User discussions
Date:  
To: User discussions
Subject: Re: [ros-users] Issues Communicating with Rviz
>
>
> If you could clarify for me, it would be greatly appriciated
>


I've highlighted the issues below


> *> void jointCallback(const sensor_msgs::JointStateConstPtr& state)
> > {
> >
> >
>
> >  ros::NodeHandle n;
> >     ros::Publisher joint_pub =
> > n.advertise<sensor_msgs::JointState>("joint_states", 1);

>
>
> *
>


Here you're creating the Publisher inside your subscription callback
(jointCallback). Due to how ROS works, it can take some time for
subscribers to connect to you once you've created the publisher, so the
first few messages you publish may not get received. Because you're
creating/destroying the Publisher every time you receive a message, it's
likely no-one will ever receive the message you're trying to publish.


> *>
>
> >     tf::TransformBroadcaster broadcaster;
> >     ros::Rate loop_rate(30);

>
>
> *
>


You're doing the same thing with the TransformBroadcaster


> *
>
> >         broadcaster.sendTransform(odom_trans);

>
> *
>


Here you're sending the same odom->world transform as the other broadcaster.
This will cause them to fight about who has the correct information.

I would recommend using a class that contains the Publisher and
TransformBroadcaster, something like:
class JointBroadcaster
{
public:
JointBroadcaster(); // advertise here

void jointCallback(...);

private:
ros::Publisher joint_pub_;
tf::TransformBroadcaster tf_broadcaster_;
};

Josh