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

ROS .msg depends

asked 2017-04-19 07:34:03 -0500

slavaglaps gravatar image

I have two packages: inpub and insub

in inpub CmakeList.txt

find_package(catkin REQUIRED COMPONENTS
  insub
  roscpp
  rospy
  std_msgs)

catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES inpub
# CATKIN_DEPENDS message_runtime
#  DEPENDS system_lib
)

include_directories(
  ${catkin_INCLUDE_DIRS}
)

in .xml

<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>insub</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>message_generation</build_depend>
<run_depend>rospy</run_depend>
<run_depend>insub</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>message_runtime</run_depend>

1) When I in inpub.py

import insub

A take error

File "/home/slavaglaps/two/src/test/scripts/inpub.py", line 6, in <module>
    import insub
ImportError: No module named insub

How can I import it correctly?

2) In the insub package I have inpub/msg/TwoInts.msg

How do I transfer this class? I also read in the documentation about a separate package for .msg. Can you talk more about this?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-04-20 05:35:11 -0500

updated 2017-04-20 05:39:05 -0500

In order to help cmake generate your messages you need to have some declarations on your CMakeLists.txt For example, for insub you should have something like this:

cmake_minimum_required(VERSION 2.8.3)
project(insub)

find_package(catkin REQUIRED COMPONENTS
  std_msgs
  message_generation
)

add_message_files(
  FILES
  TwoInts.msg
)

generate_messages(
    DEPENDENCIES
    std_msgs
)

catkin_package(CATKIN_DEPENDS std_msgs)

Of course this is just a speculation, but it would most definitely work for you. Also, you will have to create the corresponding package.xml file, just like you've done for inpub.

Good luck!

P.S. The "no module named insub" error could be due to wrong or non-existent CMakeLists.txt and package.xml for insub, or wrong catkin workspace configuration. Check if you have these lines inside your ~/.bashrc:

source /opt/ros/$ROS_DISTRO/setup.bash

and

source ~/catkin_ws/devel/setup.bash
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-04-19 07:34:03 -0500

Seen: 551 times

Last updated: Apr 20 '17