Moveit move_group interface in C++

asked 2016-01-19 02:15:45 -0500

chiprof gravatar image

updated 2016-01-19 02:55:37 -0500

gvdhoorn gravatar image

Hello, I am new to ros and trying to move my robot arm using c++ and moveit.

My cmakelist.txt file is like this:

cmake_minimum_required(VERSION 2.8.3)
project(jaco_feeder)

#if(WIN32)
 # set(OpenCV_DIR "d:/libs/opencv-2.4.8/build")
#else()
 #set(OpenCV_INCLUDE_DIR "/usr/local/include/opencv2")
#endif()
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs rosconsole actionlib actionlib_msgs dynamic_reconfigure 
message_generation cv_bridge image_transport moveit_ros_planning_interface geometry_msgs)
find_package(Boost REQUIRED COMPONENTS thread system)
find_package (OpenCV REQUIRED)
find_package (Eigen REQUIRED)
##Moveit movegroup begins
# include_directories(include)
include_directories(
    include
    ${catkin_INCLUDE_DIRS}
    ${Boost_INCLUDE_DIRS}
    ${actionlib_INCLUDE_DIRS}
    ${Eigen_INCLUDE_DIRS}
)
##Moveit movegroup ends
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} )
include_directories (SYSTEM ${Boost_INCLUDE_DIR} ${EIGEN_INCLUDE_DIRS})
#include_directories( ${OpenCV_INCLUDE_DIRS} )
set(CMAKE_CXX_FLAGS "-O2 -W -Wall -Wextra -Wno-unused-parameter -fno-strict-aliasing -pthread -std=c++0x")
#set (OpenCV_LIBS opencv_core opencv_imgproc opencv_highgui opencv_ml opencv_video opencv_features2d opencv_calib3d opencv_objdetect opencv_contrib opencv_legacy opencv_flann)
##Libraries##
add_library(Navigator src/Navigator.cpp)
target_link_libraries(Navigator ${catkin_LIBRARIES})
add_library(Vision src/Vision.cpp)
target_link_libraries(Vision ${OpenCV_LIBS} ${catkin_LIBRARIES} Navigator)
add_library(JointStatePublisher src/JointStatePublisher.cpp)
target_link_libraries(JointStatePublisher Navigator)
add_library(JointStateListener src/JointStateListener.cpp)
target_link_libraries(JointStateListener Navigator)
add_library(Controller src/JController.cpp)
target_link_libraries(Controller Navigator Vision)
##Executables ##
add_executable(jaco_feeder_main src/feeder_main.cpp ${Boost_LIBRARIES} ${catkin_LIBRARIES} ) 
target_link_libraries(jaco_feeder_main Navigator JointStatePublisher JointStateListener Vision Controller ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
#target_link_libraries(jaco_feeder_main Vision  ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})

However, when I include the movegroup interface in my header like so:

#include <moveit/planning_scene_interface/planning_scene_interface.h>

I get loads of errors while building the package. The error I get is below:

[ 40%] Building CXX object jaco_feeder/CMakeFiles/Controller.dir/src/JController.cpp.o
cd /home/chinwe/catkin_ws/build/jaco_feeder && /usr/bin/c++   -DController_EXPORTS -DROS_BUILD_SHARED_LIBS=1 -DROS_PACKAGE_NAME=\"jaco_feeder\" -DROSCONSOLE_BACKEND_LOG4CXX -O2 -W -Wall -Wextra -Wno-unused-parameter -fno-strict-aliasing -pthread -std=c++0x -fPIC -I/home/chinwe/catkin_ws/src/jaco_feeder/include -I/opt/ros/hydro/include -I/opt/ros/hydro/include/opencv -isystem /usr/include/eigen3 -I/usr/include/pcl-1.7    -o CMakeFiles/Controller.dir/src/JController.cpp.o -c /home/chinwe/catkin_ws/src/jaco_feeder/src/JController.cpp
In file included from /opt/ros/hydro/include/moveit/kinematics_base/kinematics_base.h:41:0,
                 from /opt/ros/hydro/include/moveit/robot_model/joint_model_group.h:43,
                 from /opt/ros/hydro/include/moveit/robot_model/robot_model.h:48,
                 from /opt/ros/hydro/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/hydro/include/moveit/planning_scene_interface/planning_scene_interface.h:40,
                 from /home/chinwe/catkin_ws/src/jaco_feeder/include/JController.h:19,
                 from /home/chinwe/catkin_ws/src/jaco_feeder/src/JController.cpp:7:
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:72:12: error: expected identifier before numeric constant
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:72:12: error: expected ‘}’ before numeric constant
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:72:12: error: expected unqualified-id before numeric constant
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:98:63: error: ‘ContainerAllocator’ was not declared in this scope
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:98:81: error: template argument 1 is invalid
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:98:83: error: template argument 1 is invalid
/opt/ros/hydro/include/moveit_msgs/MoveItErrorCodes.h:98 ...
(more)
edit retag flag offensive close merge delete

Comments

Please format your question properly when posting. I've used the Preformatted text button to clean it up a bit (the one with 101010 on it). Console copy/pastes (and thus your question) are unreadable otherwise.

gvdhoorn gravatar image gvdhoorn  ( 2016-01-19 02:56:43 -0500 )edit

Thank you for that

chiprof gravatar image chiprof  ( 2016-01-19 05:05:36 -0500 )edit

I cant read much from error snapshot you have posted. I was getting errors related to include file at one time, i tried installing moveit from source and it worked. So if you haven't tried that i would suggest you to do so.

mvish7 gravatar image mvish7  ( 2018-12-10 00:19:09 -0500 )edit