CentroEPiaggio / kuka-lwr

Software related to the KUKA LWR 4+: for real and for simulation.
The Unlicense
101 stars 81 forks source link

Building Problem #101

Open marcingajewski14 opened 4 years ago

marcingajewski14 commented 4 years ago

Hi, I am begginer in ROS and it is important for me to use package Kuka LWR for my project. I am using ROS Melodic, Gazebo 9. I added package and before launching examples I wanted to build workspace using catkin buildcommand. I've got these errors:

`marcin@marcin-VirtualBox:~/ws_moveit/src$ catkin build

Profile: default Extending: [explicit] /opt/ros/melodic Workspace: /home/marcin/ws_moveit

Build Space: [exists] /home/marcin/ws_moveit/build Devel Space: [exists] /home/marcin/ws_moveit/devel Install Space: [unused] /home/marcin/ws_moveit/install Log Space: [exists] /home/marcin/ws_moveit/logs Source Space: [exists] /home/marcin/ws_moveit/src DESTDIR: [unused] None

Devel Space Layout: linked Install Space Layout: None

Additional CMake Args: -DCMAKE_BUILD_TYPE=Release Additional Make Args: None Additional catkin Make Args: None Internal Make Job Server: True Cache Job Environments: False

Whitelisted Packages: None Blacklisted Packages: None

Workspace configuration appears valid.

[build] Found '52' packages in 0.0 seconds.
[build] Package table is up to date.
Starting >>> fri_library_ros
Finished <<< fri_library_ros [ 0.3 seconds ]
Starting >>> geometric_shapes
Finished <<< geometric_shapes [ 0.3 seconds ]
Starting >>> lwr_console
Finished <<< lwr_console [ 0.2 seconds ]
Starting >>> lwr_description
Finished <<< lwr_description [ 0.2 seconds ]
Starting >>> lwr_hw


Errors << lwr_hw:make /home/marcin/ws_moveit/logs/lwr_hw/build.make.003.log /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp: In member function ‘void lwr_hw::LWRHW::registerJointLimits(const string&, const hardware_interface::JointHandle&, const hardware_interface::JointHandle&, const hardware_interface::JointHandle&, const urdf::Model, double, double, double, double, double)’: /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:245:83: error: conversion from ‘urdf::JointConstSharedPtr {aka std::shared_ptr}’ to non-scalar type ‘const boost::shared_ptr’ requested const boost::shared_ptr urdf_joint = urdf_model->getJoint(joint_name);


/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:246:93: error: conversion from ‘urdf::JointConstSharedPtr {aka std::shared_ptr<const urdf::Joint>}’ to non-scalar type ‘const boost::shared_ptr<const urdf::Joint>’ requested
       const boost::shared_ptr<const urdf::Joint> urdf_joint_sitffness = urdf_model->getJoint(joint_name + std::string("_stiffness"));
                                                                         ~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:250:70: error: no matching function for call to ‘getJointLimits(const boost::shared_ptr<const urdf::Joint>&, joint_limits_interface::JointLimits&)’
         if (joint_limits_interface::getJointLimits(urdf_joint, limits))
                                                                      ^
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:19:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:75:13: note: candidate: bool joint_limits_interface::getJointLimits(const string&, const ros::NodeHandle&, joint_limits_interface::JointLimits&)
 inline bool getJointLimits(const std::string& joint_name, const ros::NodeHandle& nh, JointLimits& limits)
             ^~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:75:13: note:   candidate expects 3 arguments, 2 provided
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:20:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:48:13: note: candidate: bool joint_limits_interface::getJointLimits(urdf::JointConstSharedPtr, joint_limits_interface::JointLimits&)
 inline bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits& limits)
             ^~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:48:13: note:   no known conversion for argument 1 from ‘const boost::shared_ptr<const urdf::Joint>’ to ‘urdf::JointConstSharedPtr {aka std::shared_ptr<const urdf::Joint>}’
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:252:90: error: no matching function for call to ‘getJointLimits(const boost::shared_ptr<const urdf::Joint>&, joint_limits_interface::JointLimits&)’
         if (joint_limits_interface::getJointLimits(urdf_joint_sitffness, limits_stiffness))
                                                                                          ^
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:19:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:75:13: note: candidate: bool joint_limits_interface::getJointLimits(const string&, const ros::NodeHandle&, joint_limits_interface::JointLimits&)
 inline bool getJointLimits(const std::string& joint_name, const ros::NodeHandle& nh, JointLimits& limits)
             ^~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:75:13: note:   candidate expects 3 arguments, 2 provided
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:20:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:48:13: note: candidate: bool joint_limits_interface::getJointLimits(urdf::JointConstSharedPtr, joint_limits_interface::JointLimits&)
 inline bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits& limits)
             ^~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:48:13: note:   no known conversion for argument 1 from ‘const boost::shared_ptr<const urdf::Joint>’ to ‘urdf::JointConstSharedPtr {aka std::shared_ptr<const urdf::Joint>}’
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:254:79: error: no matching function for call to ‘getSoftJointLimits(const boost::shared_ptr<const urdf::Joint>&, joint_limits_interface::SoftJointLimits&)’
         if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits))
                                                                               ^
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:19:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:194:13: note: candidate: bool joint_limits_interface::getSoftJointLimits(const string&, const ros::NodeHandle&, joint_limits_interface::SoftJointLimits&)
 inline bool getSoftJointLimits(const std::string& joint_name, const ros::NodeHandle& nh, SoftJointLimits& soft_limits)
             ^~~~~~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_rosparam.h:194:13: note:   candidate expects 3 arguments, 2 provided
In file included from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/include/lwr_hw/lwr_hw.h:20:0,
                 from /home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:1:
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:84:13: note: candidate: bool joint_limits_interface::getSoftJointLimits(urdf::JointConstSharedPtr, joint_limits_interface::SoftJointLimits&)
 inline bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits& soft_limits)
             ^~~~~~~~~~~~~~~~~~
/opt/ros/melodic/include/joint_limits_interface/joint_limits_urdf.h:84:13: note:   no known conversion for argument 1 from ‘const boost::shared_ptr<const urdf::Joint>’ to ‘urdf::JointConstSharedPtr {aka std::shared_ptr<const urdf::Joint>}’
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp: In member function ‘virtual bool lwr_hw::LWRHW::canSwitch(const std::__cxx11::list<hardware_interface::ControllerInfo>&, const std::__cxx11::list<hardware_interface::ControllerInfo>&) const’:
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:412:15: error: ‘const struct hardware_interface::ControllerInfo’ has no member named ‘hardware_interface’
       if( it->hardware_interface.compare( std::string("hardware_interface::VelocityJointInterface") ) == 0 )
               ^~~~~~~~~~~~~~~~~~
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:419:15: error: ‘const struct hardware_interface::ControllerInfo’ has no member named ‘hardware_interface’
       if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 )
               ^~~~~~~~~~~~~~~~~~
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:425:20: error: ‘const struct hardware_interface::ControllerInfo’ has no member named ‘hardware_interface’
       else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 )
                    ^~~~~~~~~~~~~~~~~~
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp: In member function ‘virtual void lwr_hw::LWRHW::doSwitch(const std::__cxx11::list<hardware_interface::ControllerInfo>&, const std::__cxx11::list<hardware_interface::ControllerInfo>&)’:
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:459:15: error: ‘const struct hardware_interface::ControllerInfo’ has no member named ‘hardware_interface’
       if( it->hardware_interface.compare( std::string("hardware_interface::PositionJointInterface") ) == 0 )
               ^~~~~~~~~~~~~~~~~~
/home/marcin/ws_moveit/src/kuka-lwr-ros/kuka_lwr/lwr_hw/src/lwr_hw.cpp:465:20: error: ‘const struct hardware_interface::ControllerInfo’ has no member named ‘hardware_interface’
       else if( it->hardware_interface.compare( std::string("hardware_interface::EffortJointInterface") ) == 0 )
                    ^~~~~~~~~~~~~~~~~~
make[2]: *** [CMakeFiles/lwr_hw.dir/src/lwr_hw.cpp.o] Error 1
make[1]: *** [CMakeFiles/lwr_hw.dir/all] Error 2
make: *** [all] Error 2
cd /home/marcin/ws_moveit/build/lwr_hw; catkin build --get-env lwr_hw | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -
...............................................................................
Failed     << lwr_hw:make                                     [ Exited with code 2 ]
Failed    <<< lwr_hw                                          [ 5.2 seconds ]  
Abandoned <<< lwr_launch                                      [ Unrelated job failed ]
Abandoned <<< mani                                            [ Unrelated job failed ]
Abandoned <<< moveit_msgs                                     [ Unrelated job failed ]
Abandoned <<< moveit_resources                                [ Unrelated job failed ]
Abandoned <<< passive_ds_control                              [ Unrelated job failed ]
Abandoned <<< robot_motion_generation                         [ Unrelated job failed ]
Abandoned <<< rviz_visual_tools                               [ Unrelated job failed ]
Abandoned <<< srdfdom                                         [ Unrelated job failed ]
Abandoned <<< lwr_fri                                         [ Unrelated job failed ]
Abandoned <<< moveit_commander                                [ Unrelated job failed ]
Abandoned <<< panda_moveit_config                             [ Unrelated job failed ]
Abandoned <<< peg_lwr_launch                                  [ Unrelated job failed ]
Abandoned <<< peg_lwr_robot                                   [ Unrelated job failed ]
Abandoned <<< lwr_controllers                                 [ Unrelated job failed ]
Abandoned <<< lwr_ros_interface                               [ Unrelated job failed ]
Abandoned <<< lwr_ros_client                                  [ Unrelated job failed ]
Abandoned <<< lwr_simple_example                              [ Unrelated job failed ]
Abandoned <<< single_lwr_robot                                [ Unrelated job failed ]
Abandoned <<< single_lwr_moveit                               [ Unrelated job failed ]
Abandoned <<< moveit_core                                     [ Unrelated job failed ]
Abandoned <<< chomp_motion_planner                            [ Unrelated job failed ]
Abandoned <<< moveit_chomp_optimizer_adapter                  [ Unrelated job failed ]
Abandoned <<< moveit_ros_occupancy_map_monitor                [ Unrelated job failed ]
Abandoned <<< moveit_ros_perception                           [ Unrelated job failed ]
Abandoned <<< moveit_ros_planning                             [ Unrelated job failed ]
Abandoned <<< moveit_fake_controller_manager                  [ Unrelated job failed ]
Abandoned <<< moveit_kinematics                               [ Unrelated job failed ]
Abandoned <<< moveit_planners_ompl                            [ Unrelated job failed ]
Abandoned <<< moveit_ros_move_group                           [ Unrelated job failed ]
Abandoned <<< moveit_ros_manipulation                         [ Unrelated job failed ]
Abandoned <<< moveit_ros_robot_interaction                    [ Unrelated job failed ]
Abandoned <<< moveit_ros_warehouse                            [ Unrelated job failed ]
Abandoned <<< moveit_ros_benchmarks                           [ Unrelated job failed ]
Abandoned <<< moveit_ros_planning_interface                   [ Unrelated job failed ]
Abandoned <<< moveit_jog_arm                                  [ Unrelated job failed ]
Abandoned <<< moveit_planners_chomp                           [ Unrelated job failed ]
Abandoned <<< moveit_ros_visualization                        [ Unrelated job failed ]
Abandoned <<< moveit_setup_assistant                          [ Unrelated job failed ]
Abandoned <<< moveit_simple_controller_manager                [ Unrelated job failed ]
Abandoned <<< moveit_ros_control_interface                    [ Unrelated job failed ]
Abandoned <<< moveit_visual_tools                             [ Unrelated job failed ]
Abandoned <<< moveit_tutorials                                [ Unrelated job failed ]
[build] Summary: 4 of 47 packages succeeded.                                   
[build]   Ignored:   5 packages were skipped or are blacklisted.               
[build]   Warnings:  None.                                                     
[build]   Abandoned: 42 packages were abandoned.                               
[build]   Failed:    1 packages failed.                                        
[build] Runtime: 7.4 seconds total. `

I'll be really thankful, if someone can help me what the problem is. 
smhadisadati commented 4 years ago

Hi. the package is for ROS Indigo Ubuntu 14. You may use:

for ( std::list::const_iterator ci_it = start_list.begin(); ci_it != start_list.end(); ++ci_it ) { for( std::vector::const_iterator it = ci_it->claimed_resources.begin(); it != ci_it->claimed_resources.end(); ++it) { ... } }

instead of

for ( std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it ) { ... }

Do the same for similar errors.

smhadisadati commented 4 years ago

Later you get more errors with FRI that I am working on at the moment. Better to run it on ROS Indigo Ubuntu 14 if you want no hassles. Alternatively, apparently the simulator works on ROS Kinetic Ubuntu 16 (what I have) if you remove all the unnecessary packages (working on it now). Any luck on your side?