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

ROS 1 Correct way to declare Python dependencies

asked 2019-05-20 18:09:12 -0500

screen33 gravatar image

updated 2019-05-26 17:29:39 -0500

My package my_package also comes with an alternate my_package_msgs.

1. Dependency on another package's Python message Python lib in my_package/src has a from my_package_msgs.msg import SomeMsg statement. Currently my_package has a declared dependency my_package_msgs in package.xml (runtime and build) as well as in CMAkeLists.txt (in find_package and catkin_package). At first compiling though, catkin_make fails while it's compiling messages of dynamic reconfigure:

[  1%] Built target _robot_core_msgs_generate_messages_check_deps_CalibrationCmdActionGoal
Traceback (most recent call last):
  File "/home/screen33/ros_ws/src/my_package/cfg/JointTrajectoryActionServer.cfg", line 30, in <module>
    from my_package.states import joint_names
  File "/home/screen33/ros_ws/src/my_package/src/my_package/joints.py", line 4, in <module>
    from my_package_msgs.msg import MachineJoint
ImportError: No module named msg

The message MachineJoint is defined in package my_package_msgs that should be built BEFORE my_package. To fix it, it is necessary to sourcesetup.bash and re-compile. How to fix it so that we just have to compile once?

The package.xml has the following deps:

<build_depend>rospy</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>control_msgs</build_depend>
<build_depend>trajectory_msgs</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>my_package_msgs</build_depend>

<exec_depend>rospy</exec_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>control_msgs</exec_depend>
<exec_depend>trajectory_msgs</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>my_package_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>

And the CMakeLists.txt is the following:

cmake_minimum_required(VERSION 2.8.3)
project(my_package)

find_package(catkin REQUIRED
  COMPONENTS
  rospy
  actionlib
  sensor_msgs
  std_msgs
  control_msgs
  trajectory_msgs
  dynamic_reconfigure
  my_package_msgs
)

catkin_python_setup()

generate_dynamic_reconfigure_options(
  cfg/JointTrajectoryActionServer.cfg
)

catkin_package(
  CATKIN_DEPENDS
  rospy
  actionlib
  sensor_msgs
  std_msgs
  control_msgs
  trajectory_msgs
  my_package_msgs
  message_runtime
  dynamic_reconfigure
)

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

2. Dependency on a Python package Python lib in my_package/src also needs numpy, pygame and a couple of other Python pacakges. What's the best way to make them automatically installed? An additionnal statement setup_args['requires'] = ['numpy', 'pygame'] in the CMakeLists.txt template with catkin_python_setup activated seems ignored. How can we prevent a manual install of these packages with pip?

edit retag flag offensive close merge delete

Comments

Can you also please update your question with the code that's giving you this error, your package.xml, and CMakeLists.txt (sorry, I should have asked for these earlier too). Also, do you have the msg directory in your my_package_msgs package?

jayess gravatar image jayess  ( 2019-05-21 12:58:28 -0500 )edit

Question updated with CMakeLists and package deps! Yes my_package_msgs has a msg folder ; and anyway everything works as expected as long as I compile at least twice. So that's only an issue of order in of compiling rules and deps I think.

screen33 gravatar image screen33  ( 2019-05-26 17:32:06 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-05-20 18:13:54 -0500

jayess gravatar image

updated 2019-05-20 18:28:50 -0500

For your first point, if you need a message from another package, add that package as a dependency.

For the second point, as stated in the docs, Python dependencies should be listed in your package.xml file

If you have written non-ROS Python packages before, you have probably used the requires field in the distuils setup function. This field, however, has no meaning in ROS.

All your Python dependencies should be specified in package.xml as e.g. <run_depend>python-numpy</run_depend> (for older version 1 of package.xml) or <exec_depend>python-numpy</exec_depend> (if you use format 2 of package.xml

Not all Python or pip packages are mapped to ROS dependencies. For a quick check, try running rosdep resolve python-mypackage or rosdep resolve python-mypackage-pip if you want to add a dependency on mypackage Python package. If these calls return error, you may want to search through the python.yaml file in rosdep for similar names.

If you list your dependencies in your package.xml file, then rosdep should be able to list them and install them using the user's package manager, if available (as far as I'm aware).

edit flag offensive delete link more

Comments

Great thanks, I had missed that discrete-but-primordial point! Does it mean than in general it is a good idea to run rosdep before any catkin_make? i'm actually not used to run rosdep at some time. Any idea for my issue "1."?

screen33 gravatar image screen33  ( 2019-05-20 18:25:19 -0500 )edit
1

You'll need to update your question with any and all errors, messages, etc. that are output to your terminal.

jayess gravatar image jayess  ( 2019-05-20 18:26:31 -0500 )edit

Yes, done!

screen33 gravatar image screen33  ( 2019-05-21 05:04:20 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-05-20 18:09:12 -0500

Seen: 6,753 times

Last updated: May 26 '19