"error: ‘__s_getServerMD5Sum’ is not a member of" when adding a service to an existing class
TL;DR
Trying to add two new services to a class definition but we are getting and error saying __s_getServerMD5Sum is not a member of each of them. Our new services are implemented exactly as all of the existing services.
Details
We are implementing a ur_modern_driver node from: github.com/ThomasTimm/ur_modern_driver
Our classes are being added to ur_ros_wrapper.cpp. With an unmodified installation of this node everything compiles and runs as expected. However, we need to add additional services to the RosWrapper class to provide control of the robots free drive mode.
The two new services are called enterFreeDriveMode and exitFreeDriveMode.
As far as we can tell we have implemented our new services correctly. In short our service implementation looks like this:
//create the service servers
ros::ServiceServer enterFreeDriveMode_srv_;
ros::ServiceServer exitFreeDriveMode_srv_;
//initialize the services
enterFreeDriveMode_srv_ = nh_.advertiseService("ur_driver/enterFreeDriveMode", &RosWrapper::enterFreeDriveMode, this);
exitFreeDriveMode_srv_ = nh_.advertiseService("ur_driver/exitFreeDriveMode", &RosWrapper::exitFreeDriveMode, this);
//service callback class methods
bool enterFreeDriveMode(ur_msgs::EnterFreeDriveModeRequest& req, ur_msgs::EnterFreeDriveModeResponse& resp) {
robot_.enterFreeDriveMode(true);
resp.success = true;
return resp.success;
}
bool exitFreeDriveMode(ur_msgs::ExitFreeDriveModeRequest& req, ur_msgs::ExitFreeDriveModeResponse& resp) {
robot_.exitFreeDriveMode(true);
resp.success = true;
return resp.success;
}
//EnterFreeDriveMode.srv and ExitFreeDriveMode.srv have the exact same definition
bool start
---
bool success
When we run catkin_make we get the following errors:
[ 88%] Building CXX object ur_modern_driver/CMakeFiles/ur_driver.dir/src/ur_ros_wrapper.cpp.o In file included from /opt/ros/kinetic/include/ros/service_client.h:33:0,
from /opt/ros/kinetic/include/ros/node_handle.h:35,
from /opt/ros/kinetic/include/ros/ros.h:45,
from /home/evilbot/catkin_ws/src/ur_modern_driver/include/ur_modern_driver/do_output.h:23,
from /home/evilbot/catkin_ws/src/ur_modern_driver/include/ur_modern_driver/ur_realtime_communication.h:23,
from /home/evilbot/catkin_ws/src/ur_modern_driver/include/ur_modern_driver/ur_driver.h:24,
from /home/evilbot/catkin_ws/src/ur_modern_driver/src/ur_ros_wrapper.cpp:19: /opt/ros/kinetic/include/ros/service_traits.h: In instantiation of ‘static const char* ros::service_traits::MD5Sum<M>::value() [with M = ur_msgs::enterFreeDriveModeRequest_<std::allocator<void>>]’: >/opt/ros/kinetic/include/ros/service_traits.h:79:102: required from ‘const char* ros::service_traits::md5sum() [with M
= ur_msgs::enterFreeDriveModeRequest_<std::allocator<void>>]’ >/opt/ros/kinetic/include/ros/advertise_service_options.h:60:25: required from ‘void ros::AdvertiseServiceOptions::init(const string&, const boost::function<bool(MReq&, MRes&)>&) [with MReq = ur_msgs::enterFreeDriveModeRequest_<std::allocator<void>>; MRes = >ur_msgs::enterFreeDriveModeResponse_<std::allocator<void> >; std::__cxx11::string = >std::__cxx11::basic_string<char>]’ /opt/ros/kinetic/include/ros/node_handle.h:881:5: required from ‘ros::ServiceServer ros::NodeHandle::advertiseService(const string&, bool (T::*)(MReq&, MRes&), T*) [with T = RosWrapper; MReq = ur_msgs::enterFreeDriveModeRequest_<std::allocator<void>>; MRes = > > >ur_msgs::enterFreeDriveModeResponse_<std::allocator<void>>; std::__cxx11::string = >std::__cxx11::basic_string<char>]’ /home/evilbot/catkin_ws/src/ur_modern_driver/src/ur_ros_wrapper.cpp:232:43: required from here /opt/ros/kinetic/include/ros/service_traits.h:47:34: error: ‘__s_getServerMD5Sum’ is not a member of ‘ur_msgs::enterFreeDriveModeRequest_<std::allocator<void>>’
return M::__s_getServerMD5Sum().c_str();
^ /opt/ros/kinetic/include/ros/service_traits.h: In instantiation of ‘static const char* ros::service_traits::MD5Sum<M>::value() [with M = ur_msgs::enterFreeDriveModeResponse_<std::allocator<void>>]’: >/opt/ros ...
You've lef out the most important bit of info: the
ur_msgs/EnterFreeDriveMode
andur_msgs/ExitFreeDriveMode
service definitions. Those are not standard services, so you need to include those.I'm guessing, but depending no your svc defs, it should be
resp.success.data = true;
.Also: did you create new service defs?
FInally: please edit your original question and copy-paste the compiler error message again. Then please select it and press the Preformatted Text button (the one with
101010
on it). Don't use 'block comments' for code/error msgs/etc.Updated. Sorry I should have got those the first time.
I also noted that these classes are being added to ur_ros_wrapper.cpp if you want to see the original on GH. All of the existing services use
resp.success = true;
. I'll give that a shot later today though. Thx!not sure what this means.
To add a service server:
#include
the header(s) in the file you're going to add the srv toros::ServiceServer
sSuggestion: if all you're doing is triggering something, I would not create custom services, but use std_srvs/Trigger.