Publisher or Subscriber inside a class [rosserial]
Hi, I'm using rosserial in Arduino and have a problem initializing the Publisher or Subscriber inside the class constructor:
void setup() {
DifferentialDriveRobot *my_robot = new DifferentialDriveRobot( );
}
void loop() {
...
}
And the class is implemented as (in this example, with a subscriber):
class DifferentialDriveRobot
{
...
public:
ros::NodeHandle nh;
ros::Subscriber<geometry_msgs::Twist> sub;
...
void ddr_callback(const geometry_msgs::Twist& msg) {...}
DifferentialDriveRobot() { // Constructor
nh.initNode()
sub("/cmd_vel_mux/input/teleop", ddr_callback);
nh.subscribe(sub);
}
};
And the compiling errors are the following:
error: no matching function for call to 'ros::Subscriber<geometry_msgs::twist>::Subscriber()'
note: candidate expects 3 arguments, 0 provided
error: no match for call to '(ros::Subscriber<geometry_msgs::twist>) (const char [26], void (&)(const geometry_msgs::Twist&))'
sub("/cmd_vel_mux/input/teleop", ddr_callback);
I think that this is because of the initialization of the sub
variable without any parameter. Should I declare it as a pointer?
NOTE: If I declare the ros::NodeHandle nh
and ros::Subscriber<geometry_msgs::Twist> sub("/cmd_vel_mux/input/teleop", ddr_callback)
in the main loop as global variables, the code works fine.
I'm not very familiarized using templates, so I don't know exactly if exists an good implementation for this problem in the ros_lib library.
Thanks for your help!
Update
Error message shown by the Arduino IDE when compile the answer of @DavidN:
Arduino: 1.6.12 (Linux), Board: "Arduino Leonardo"
In file included from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:0:
DifferentialDriveRobot.h:45: error: invalid use of template-name 'ros::Subscriber' without an argument list
ros::Subscriber sub;
^
sketch/DifferentialDriveRobot.h: In constructor 'DifferentialDriveRobot::DifferentialDriveRobot(DCMotor*, DCMotor*, double, double)':
DifferentialDriveRobot.h:67: error: 'sub' was not declared in this scope
sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
^
DifferentialDriveRobot.h:67: error: no matching function for call to 'ros::NodeHandle_<ArduinoHardware>::subscribe(const char [26], int, void (DifferentialDriveRobot::*)(const geometry_msgs::Twist&), DifferentialDriveRobot*)'
sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
^
sketch/DifferentialDriveRobot.h:67:96: note: candidate is:
In file included from /home/emiliano/Arduino/libraries/ros_lib/ros.h:38:0,
from sketch/DifferentialDriveRobot.h:8,
from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:
/home/emiliano/Arduino/libraries/ros_lib/ros/node_handle.h:352:12: note: template<class SubscriberT> bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::subscribe(SubscriberT&) [with SubscriberT = SubscriberT; Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]
bool subscribe(SubscriberT& s){
^
/home/emiliano/Arduino/libraries/ros_lib/ros/node_handle.h:352:12: note: template argument deduction/substitution failed:
In file included from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:0:
sketch/DifferentialDriveRobot.h:67:96: note: candidate expects 1 argument, 4 provided
sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
^
exit status 1
invalid use of template-name 'ros::Subscriber' without an argument list
Comment from @DavidN:
Is there any way to publish outside the void loop?
I think for the subscriber is easy, but for publishing is not easy. Is there any way to publish outside the void loop?
Would you create a new issue and point us there so we can give you precise feedback?
Thanks. I've created this one rosserial arduino