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

Moveit missing rosdep dependencies on raspbian jessie

asked 2016-05-30 02:49:41 -0500

cmhe gravatar image

updated 2017-01-06 02:21:48 -0500

130s gravatar image

I am currently trying to install moveit on a raspbian.

First I installed ROS indigo using these instructions. After that i followed these manual instructions to install moveit, but I could not install the dependencies.

$ rosdep update
reading in sources list data from /etc/ros/rosdep/sources.list.d
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/osx-homebrew.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/base.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/python.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/ruby.yaml
Hit https://raw.githubusercontent.com/ros/rosdistro/master/releases/fuerte.yaml
Query rosdistro index https://raw.githubusercontent.com/ros/rosdistro/master/index.yaml
Add distro "groovy"
Add distro "hydro"
Add distro "indigo"
Add distro "jade"
Add distro "kinetic"
updated cache in /home/pi/.ros/rosdep/sources.cache
$ rosdep install --from-paths src --ignore-src --rosdistro indigo -y
ERROR: the following packages/stacks could not have their rosdep keys resolved to system dependencies:
moveit_ros_benchmarks: No definition of [eigen_conversions] for OS [debian]
moveit_ros_perception: No definition of [sensor_msgs] for OS [debian]
moveit_setup_assistant: No definition of [xacro] for OS [debian]
moveit_fake_controller_manager: No definition of [pluginlib] for OS [debian]
moveit_msgs: No definition of [object_recognition_msgs] for OS [debian]
moveit_planners_ompl: No definition of [pluginlib] for OS [debian]
moveit_controller_manager_example: No definition of [pluginlib] for OS [debian]
moveit_ros_move_group: No definition of [pluginlib] for OS [debian]
moveit_ros_benchmarks_gui: No definition of [tf] for OS [debian]
moveit_ros_planning: No definition of [angles] for OS [debian]
moveit_ros_robot_interaction: No definition of [interactive_markers] for OS [debian]
moveit_ros_control_interface: No definition of [trajectory_msgs] for OS [debian]
moveit_ros_manipulation: No definition of [manipulation_msgs] for OS [debian]
moveit_commander: No definition of [python-pyassimp] for OS version [jessie]
moveit_simple_controller_manager: No definition of [actionlib] for OS [debian]
moveit_ros_warehouse: No definition of [tf] for OS [debian]
moveit_core: No definition of [tf_conversions] for OS [debian]
moveit_ros_visualization: No definition of [object_recognition_msgs] for OS [debian]
moveit_ros_planning_interface: No definition of [tf_conversions] for OS [debian]

I am new to ROS and this infrastructure, so its possible I missed something or did something wrong.

Thanks.

edit retag flag offensive close merge delete

Comments

Could it be that this happens because the rosdep indigo distribution definition does not mention debian jessie? How can I fix this?

cmhe gravatar image cmhe  ( 2016-05-30 03:04:37 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2016-06-08 02:46:39 -0500

cmhe gravatar image

I solved it myself. Here are my notes as to what I did. Maybe that will help someone in the future:

# Guide to get all moveit dependencies installed on raspbian jessie.
# Install ros as described here: wiki.ros.org/ROSberryPi/Installing%20ROS%20Indigo%20on%20Raspberry%20Pi
# Install moveit as described here: http://moveit.ros.org/install/#collapseFour
# This manual describes how to get the line: "rosdep install --from-paths src --ignore-src --rosdistro indigo -y" to work.

# Increase swap size:
$ sudo sed -i -e "s/CONF_SWAPSIZE=100/CONF_SWAPSIZE=1024/" /etc/dphys-swapfile
$ sudo reboot

$ cat /etc/apt/sources.list
deb http://mirrordirector.raspbian.org/raspbian/ jessie main contrib non-free rpi
# Uncomment line below then 'apt-get update' to enable 'apt-get source'
#deb-src http://archive.raspbian.org/raspbian/ jessie main contrib non-free rpi
#deb-src http://mirrordirector.raspbian.org/raspbian/ testing main contrib non-free rpi

$ cat /etc/apt/sources.list.d/ros-latest.list 
deb http://packages.ros.org/ros/ubuntu jessie main
deb http://packages.ros.org/ros/ubuntu trusty main
deb-src http://packages.ros.org/ros/ubuntu trusty main
deb-src http://archive.ubuntu.com/ubuntu/ trusty main universe multiverse restricted

# Lower priority for ubuntu packages
$ cat /etc/apt/preferences.d/ros-trusty 
Package: *
Pin: release o=ROS,a=trusty
Pin-Priority: 50

# Get 0.2 version of urdfdom from ubuntu source repo. Specify exact available version or deactivate deb-src from jessie beforehand
$ apt-get source -b 'urdfdom'
$ sudo dpkg -i liburdfdom0.2-dbg_0.2.10+dfsg-1_armhf.deb liburdfdom-dev_0.2.10+dfsg-1_armhf.deb liburdfdom-model0.2_0.2.10+dfsg-1_armhf.deb liburdfdom-model-state0.2_0.2.10+dfsg-1_armhf.deb liburdfdom-sensor0.2_0.2.10+dfsg-1_armhf.deb liburdfdom-tools_0.2.10+dfsg-1_armhf.deb liburdfdom-world0.2_0.2.10+dfsg-1_armhf.deb

# ros-indigo-pluginlib searches for 'liblog4cxx.so' in '/usr/lib'
# liblog4cxx10-dev is installed
sudo ln -s /usr/lib/arm-linux-gnueabihf/liblog4cxx.so /usr/lib/liblog4cxx.so

# Install all dependencies as ubuntu:trusty (in moveit directory)
$ rosdep install --from-paths src --ignore-src --rosdistro indigo -y --os=ubuntu:trusty

# Now we have installed every package required by moveit, but they are compiled for ubuntu trusty.
# Everything might work for raspbian jessie (debian jessie) too, but to be sure, I compiled every package myself in the next steps.

# Find all installed packages from trusty, that are not in jessie.
$ aptitude search -F '%p' '?narrow(?installed,?narrow(?archive(trusty),?not(?archive(jessie))))' > trusty-packages
# Remove all trusty packages:
$ cat trusty-packages | xargs sudo apt-get remove --purge -y

# Install build dependencies, that are not already mentioned in trusty-packages (and don't start with "ros-"):
$ sudo apt-get install libcppunit-dev libmongo-client-dev

# Install python module for sorting package dep order
$ sudo apt-get install python-toposort

# Small python script to order the packages with their dependencies:
$ cat depsort.py
#!/usr/bin/python2
import sys
from toposort import toposort_flatten
graph={}
for line in sys.stdin:
    if len(line.split()) == 2:
        a,b = line.split()[0], line.split()[1]
    elif len(line.split()) == 1:
        a,b = line.split()[0], None
    else:
        raise Exception, "Invalid input! Line: \"%s\"" % line
    if a not in graph:
        graph[a] = {b}
    else:
        graph[a].add(b)
for line in toposort_flatten(graph ...
(more)
edit flag offensive delete link more

Comments

I'm following these steps! Thank you for your sharing :)

collin gravatar image collin  ( 2016-12-26 20:02:13 -0500 )edit

btw, I had some problems to follow your steps, So I decided to format my SD card and start all over it again uhm... did you use Raspbian Lite or Pixel and do you think it matters?

Thank you very much

collin gravatar image collin  ( 2016-12-26 21:00:28 -0500 )edit
1

If I remember corrently I used raspbian lite. Since the project for which I did this, is finished quite a while ago and we ended up using ubuntu trusty for other reasons I can't really help any further. This was never intended to be a copy and paste solution, but should still work in general.

cmhe gravatar image cmhe  ( 2016-12-27 17:11:47 -0500 )edit

These where my notes for the more involved steps I toke while doing it, but since I fiddled around for a while, some parts might be missing or just obvious to me at that time.

cmhe gravatar image cmhe  ( 2016-12-27 17:18:35 -0500 )edit

thanks a lot! i'm currently struggling to solve this problem using RPI3 Model B and it drives me crazy -.-

collin gravatar image collin  ( 2016-12-28 00:10:00 -0500 )edit
1

answered 2016-12-30 00:48:03 -0500

collin gravatar image

updated 2017-01-15 21:02:50 -0500

For the people who wants to install Moveit! on Raspberry pi 3 Model B with Jessie.

I spent almost whole week to install Moveit! on Jessie, I tried many other solutions but I failed. However, I just found simple way to install Moveit!

Just

sudo apt-get install ros-indigo-moveit*

If you can't find any packages, just try

ps.

@renarded Sorry, I just saw it :/ I followed this link link text

And I did this steps:

sudo nano /etc/apt/sources.list.d/ros-latest.list

deb http://packages.ros.org/ros/ubuntu jessie main deb http://packages.ros.org/ros/ubuntu trusty main deb-src http://packages.ros.org/ros/ubuntu trusty main deb-src http://archive.ubuntu.com/ubuntu/ trusty main universe multiverse restricted

sudo nano /etc/apt/sources.list

deb http://mirrordirector.raspbian.org/ra... jessie main contrib non-free rpi #Uncomment line below then 'apt-get update' to enable 'apt-get source' deb-src http://archive.raspbian.org/raspbian/ jessie main contrib non-free rpi deb-src http://mirrordirector.raspbian.org/ra... testing main contrib non-free rpi

sudo apt-get update
sudo apt-get install ros-indigo-moveit*

And check again.

edit flag offensive delete link more

Comments

Did you manage to launch moveit move_group after that ? I did the same as you and I get a segfault Thread 1 "move_group" received signal SIGSEGV, Segmentation fault. ( http://answers.ros.org/question/25060... )

renarded gravatar image renarded  ( 2017-01-06 01:39:35 -0500 )edit

Are you sure you're on armhf? AFAIK there has been no binary built yet for Jessie for armhf for any ROS distro.

130s gravatar image 130s  ( 2017-01-06 02:41:04 -0500 )edit
1

@renarded Yeah it works well in Indigo. I don't know the packages are working in Kinetic :/ @130s I'm not sure the packages are actually built for armhf. But, I'm using in on my RPI3 Model B with Jessie. When I type arch it says armv7l

collin gravatar image collin  ( 2017-01-06 07:17:42 -0500 )edit

@collin What steps or tutorial did you follow to get ROS indigo running on RPI3 with Raspbian Jessie ? Same as 130s, I've never heard of that before

renarded gravatar image renarded  ( 2017-01-10 14:30:21 -0500 )edit

@renarded i updated my answers, check it and if you have more questions, just let me know.

collin gravatar image collin  ( 2017-01-15 21:03:41 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-05-30 02:49:41 -0500

Seen: 2,176 times

Last updated: Jan 15 '17