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

Custom Nodes not publishing or subscribing, why?

asked 2013-02-09 12:02:36 -0500

Toaster gravatar image

updated 2014-01-28 17:15:10 -0500

ngrennan gravatar image

Hi all,

I'm writing a couple simple nodes that should work (they build without errors), but when launched rxgraph and rosnode don't show any publish or subscribe topics from those nodes.

I'm hoping someone can point me in the right direction. I've included one of the nodes below:

edit: updated joy_to_point.cpp per K_Yousif. edit: solution from K_Yousif resolves the issue

joy_to_point.h

#include <ros/ros.h>
#include <ros/node_handle.h>
#include <sensor_msgs/Joy.h>
#include <husky_seeg/XYPoint.h>

class JoyToPoint {

private:
    // Node Handler
    ros::NodeHandle nh;

    // Subscribers
    ros::Subscriber joySub;

    // Publishers
    ros::Publisher pointPub;

    // Parameters
    double rangeAtMax;

    // Messages
    sensor_msgs::Joy joy;
    husky_seeg::XYPoint point;

public:
    JoyToPoint(ros::NodeHandle nh_);
    ~JoyToPoint(){}

    // Callbacks
    void joyCallback( const sensor_msgs::Joy::ConstPtr& j );

};

joy_to_point.cpp

#include "joy_to_point.h"

JoyToPoint::JoyToPoint(ros::NodeHandle nh_) : nh(nh_) {

    // Resolve topic names
    std::string joy_topic  = ros::names::clean(nh.resolveName("/joy"));
    ROS_DEBUG("Subscribing to:\n\t* %s", joy_topic.c_str());

    // Subscribe to input topics.
    joySub = nh.subscribe(joy_topic, 1, &JoyToPoint::joyCallback, this);

    // Get Parameters
    ros::NodeHandle local_nh("~");
    local_nh.param<double>( "range_at_max", rangeAtMax, 1 );

    // Advertise publisher
    pointPub = nh.advertise<husky_seeg::XYPoint>("/XYPoint", 1);
}

void JoyToPoint::joyCallback( const sensor_msgs::Joy::ConstPtr& j ) {
    // Convert Joystick message to a virtual point
    point.x = joy.axes[1] * rangeAtMax;
    point.y = joy.axes[0] * rangeAtMax;

    pointPub.publish(point);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "joy_to_point");
  ros::NodeHandle nh;

  JoyToPoint point(nh);

  ros::spin();
  return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2013-02-09 12:34:57 -0500

updated 2013-02-09 13:33:21 -0500

To publish, you need to add this line to your code (where you want to publish your msg) pointPub.publish(the-message-you-want-to-publish);

I think you should remove the instantiation of ros::NodeHandle nh; in your constructor. add it as an one of your private class attributes (ros::NodeHandle nh_ ). then initialize it in your constructor like this: JoyToPoint(ros::NodeHandle& nh): nh_(nh). In your main will look like this

int main(int argc, char **argv)
 {

 ros::init(argc, argv, "joy_to_point");
 ros::NodeHandle nh;
 JoyToPoint point(nh);
 ros::spin();
 return 0;
 }

`

edit flag offensive delete link more

Comments

Good catch, I'll update the above. Unfortunately the main issue still remains. Thanks!

Toaster gravatar image Toaster  ( 2013-02-09 12:38:26 -0500 )edit

I edited my answer. Hope it helps.

K_Yousif gravatar image K_Yousif  ( 2013-02-09 13:34:19 -0500 )edit

Excellent! Thank you, sir! That was my issue. I'll update the post and mark it as solved. Now for the debugging. Cheers!

Toaster gravatar image Toaster  ( 2013-02-09 13:54:34 -0500 )edit

You are welcome :). Note: to mark it as solved in the system, you have to check the tick just below where you up voted (it turns green). Otherwise your question will remain unsolved in the forums.

K_Yousif gravatar image K_Yousif  ( 2013-02-09 14:04:51 -0500 )edit

Question Tools

Stats

Asked: 2013-02-09 12:02:36 -0500

Seen: 2,528 times

Last updated: Feb 09 '13