Problem declaring a service server within a class [closed]
Hi everyone, I am a beginner in c++ especially with classes, I am trying to declare a service server within a class but it doesn't work, I have already had the same problem declaring a subscriber within a class, I tried applying the same thing to service server declaration without success.
#include "ros/ros.h"
#include "geometry_msgs/Vector3Stamped.h" //Message type for the torque values
#include "std_msgs/Float32.h"
#include "std_srvs/Empty.h"
class Torque
{
private:
std_msgs::Float32 totalTorque;
ros::NodeHandle n;
ros::Subscriber subscription_torque;
ros::Publisher publisher_torque;
ros::ServiceServer service_server_torque;
public:
void Torque(){
this->service_server_torque = n.advertiseService("/omniROS/resetTotalTorque",&Torque::resetService,this);
this->subscription_torque = this->n.subscribe("/omniROS/torque", 100,&Torque::callbackTorque,this);
this->publisher_torque = this->n.advertise<std_msgs::Float32>("/omniROS/totalTorque", 100);
}
void callbackTorque(const geometry_msgs::Vector3Stamped::ConstPtr& torque)
{
this->totalTorque.data += std::abs(torque->vector.x);
this->publisher_torque.publish(this->totalTorque);
}
void resetService(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res){
//This is a service server that will reset the totalTorque, it's a function that takes a void as input and returns a void as an output
this->totalTorque.data=0.0;
}
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "total_torque_node");
Torque torque;
// torque.initialisation();
while (ros::ok())
{
ros::spin();
}
return 0;
}
And i have the following error :
/home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp: In member function ‘void Torque::initialisation()’:
/home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp:17:108: error: no matching function for call to ‘ros::NodeHandle::advertiseService(const char [26], void (Torque::*)(std_srvs::Empty::Request&, std_srvs::Empty::Response&), Torque*)’
this->service_server_torque = n.advertiseService("/omniROS/resetTotalTorque",&Torque::resetService,this);
^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
from /home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp:1:
/opt/ros/kinetic/include/ros/node_handle.h:879:17: note: candidate: template<class T, class MReq, class MRes> ros::ServiceServer ros::NodeHandle::advertiseService(const string&, bool (T::*)(MReq&, MRes&), T*)
ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
^
/opt/ros/kinetic/include/ros/node_handle.h:879:17: note: template argument deduction/substitution failed:
/home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp:17:108: note: mismatched types ‘bool’ and ‘void’
this->service_server_torque = n.advertiseService("/omniROS/resetTotalTorque",&Torque::resetService,this);
^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
from /home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp:1:
/opt/ros/kinetic/include/ros/node_handle.h:924:17: note: candidate: template<class T, class MReq, class MRes> ros::ServiceServer ros::NodeHandle::advertiseService(const string&, bool (T::*)(ros::ServiceEvent<MReq, MRes>&), T*)
ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
^
/opt/ros/kinetic/include/ros/node_handle.h:924:17: note: template argument deduction/substitution failed:
/home/user/omniROS/omniROS_ws/src/total_torque/src/totalTorque.cpp:17:108: note: mismatched types ‘bool’ and ‘void’
this->service_server_torque = n.advertiseService("/omniROS/resetTotalTorque",&Torque::resetService,this);
^
In file included from /opt/ros/kinetic/include/ros ...
well, you haven't told us what "doesn't work" ..
Sorry I forgot to paste the error message , i just edited it