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

ROS Service in C++ not being built

asked 2019-08-28 03:59:51 -0500

BV_Pradeep gravatar image

Hi All,

I am using ROS Kinetic on ubuntu 16.04. I am trying to write a c++ service to send some multi array data on request from the client from server I wrote the following code for that in c++

service definition file : RequestWaypoints.srv

---
int64multiarray waypoints

RequestWaypoints_server.cpp

#include "ros/ros.h"
#include "visualize_waypoints/RequestWaypoints.h"

float waypoints[9][3] = {
              {-6.922, 12.437,-1.315},
              {3.067, -17.730, -1.315},
              {3.067, -17.730, -2.956},
              {-1.645, -19.531,-2.956},
              {-1.645, -19.531,1.892},
              {-12.163, 10.458,1.892},
              {-12.163, 10.458,0.351},
              {-6.922, 12.437,0.351},
              {-6.922, 12.437,-1.315}
            };


bool send_waypoints(visualize_waypoints::RequestWaypoints::Request  &req,
         visualize_waypoints::RequestWaypoints::Response &res)
{
  res.waypoints = waypoints;
  return true;
}

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

  ros::ServiceServer service = n.advertiseService("RequestWaypoints", send_waypoints);
  ROS_INFO("Waypoints were sent.");
  ros::spin();

  return 0;
}

RequestWaypoints_client.cpp

#include "ros/ros.h"
#include "visualize_waypoints/RequestWaypoints.h"
#include <cstdlib>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "visualize_waypoints_client");

  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");

  visualize_waypoints::RequestWaypoints srv;
  waypoints = client.call(srv)
  ROS_INFO("Received Waypoints are : %f", (float)srv.response.waypoints);
  return 0;
}

I added following lines of code in Package.xml

  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_depend>message_generation</build_depend>

  <build_export_depend>roscpp</build_export_depend>
  <build_export_depend>rospy</build_export_depend>
  <build_export_depend>std_msgs</build_export_depend>

  <exec_depend>roscpp</exec_depend>
  <exec_depend>rospy</exec_depend>
  <exec_depend>std_msgs</exec_depend>
  <exec_depend>message_runtime</exec_depend>

I added following code in cmakelist.txt file

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  message_generation
)

add_service_files(
   FILES
   RequestWaypoints.srv
 )

generate_messages(
   DEPENDENCIES
   std_msgs
 )
add_executable(RequestWaypoints_server src/scripts/RequestWaypoints_server.cpp)
target_link_libraries(RequestWaypoints_server ${catkin_LIBRARIES})
add_dependencies(RequestWaypoints_server RequestWaypoints_gencpp)

add_executable(RequestWaypoints_client src/scripts/RequestWaypoints_client.cpp)
target_link_libraries(RequestWaypoints_client ${catkin_LIBRARIES})
add_dependencies(RequestWaypoints_client RequestWaypoints_gencpp)

Once I run catkin_make I get following error

Base path: /home/rnd424/ros_ws
Source space: /home/rnd424/ros_ws/src
Build space: /home/rnd424/ros_ws/build
Devel space: /home/rnd424/ros_ws/devel
Install space: /home/rnd424/ros_ws/install
####
#### Running command: "make cmake_check_build_system" in "/home/rnd424/ros_ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/rnd424/ros_ws/devel
-- Using CMAKE_PREFIX_PATH: /home/rnd424/ros_ws/devel;/opt/ros/kinetic
-- This workspace overlays: /home/rnd424/ros_ws/devel;/opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/rnd424/ros_ws/build/test_results
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- Found gtest sources under '/usr/src/gmock': gtests will be built
-- Using Python nosetests: /usr/bin/nosetests-2.7
-- catkin 0.7.18
-- BUILD_SHARED_LIBS is on
-- BUILD_SHARED_LIBS is on
-- Using CATKIN_WHITELIST_PACKAGES: visualize_waypoints
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~  traversing 1 packages in topological order:
-- ~~  - visualize_waypoints
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'visualize_waypoints'
-- ==> add_subdirectory(visualize_waypoints)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
/opt/ros/kinetic/share/genmsg/cmake/pkg-genmsg.cmake.em:56: error: <class 'genmsg.base.InvalidMsgSpec'>: Invalid declaration: int64multiarray
Traceback (most recent call last):
  File "/usr/bin/empy", line 3302, in <module>
    if __name__ == '__main__': main()
  File "/usr/bin/empy", line 3300, in main
    invoke(sys ...
(more)
edit retag flag offensive close merge delete

Comments

having same issue here. the c++ source file is unable to include the ros service message :/

Haresh Miriyala gravatar image Haresh Miriyala  ( 2020-06-24 14:55:27 -0500 )edit

I guess there is an issue with either your includes, how you set up your dependencies or your service file. Please open a new question and provide the relevant details. Thanks.

mgruhler gravatar image mgruhler  ( 2020-06-25 07:19:34 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-08-28 04:04:32 -0500

mgruhler gravatar image

The relevant error message is:

Invalid declaration: int64multiarray

I.e., the service definition is wrong. It needs to be

---
Int64MultiArray waypoints

Note the case of the letters. This is case sensitive! See the std_msgs type definition for Int64MultiArray for reference.

edit flag offensive delete link more

Comments

Hi mgruhler,

I changed the imt64MultiAraay to int64[] I get the following error

CMake Error at visualize_waypoints/CMakeLists.txt:159 (add_executable):
  Cannot find source file:
    src/RequestWaypoints_client.cpp

  Tried extensions .c .C .c++ .cc .cpp .cxx .m .M .mm .h .hh .h++ .hm .hpp
  .hxx .in .txx

CMake Error at visualize_waypoints/CMakeLists.txt:155 (add_executable):
  Cannot find source file:
    src/RequestWaypoints_server.cpp

  Tried extensions .c .C .c++ .cc .cpp .cxx .m .M .mm .h .hh .h++ .hm .hpp
  .hxx .in .txx
CMake Error: CMake can not determine linker language for target: RequestWaypoints_client
CMake Error: Cannot determine link language for target "RequestWaypoints_client".
CMake Error: CMake can not determine linker language for target: RequestWaypoints_server
CMake Error: Cannot determine link language for target "RequestWaypoints_server"

How to resolve this issue ?

BV_Pradeep gravatar image BV_Pradeep  ( 2019-08-28 05:16:33 -0500 )edit

This is another totally unrelated issue. You probably have specified a path in your CMakeLists.txt that doesn't exist. The error points to src/RequestWaypoints_client/server.cpp, whereas theCMakeLists.txtyou posted above had a (in my opinion unnecessary)scripts` subdirectory between.

In general, for a specific question like the above, if this is solved, please mark the appropriate answer as correct by clicking on the checkmark next to the answer and open a new question with any follow-up questions that don't relate directly to the first one.

If follow-up questions relate to the original issue, please edit your question instead of only commenting with follow-up stuff.

mgruhler gravatar image mgruhler  ( 2019-08-28 05:31:18 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-08-28 03:59:51 -0500

Seen: 1,015 times

Last updated: Jun 24 '20