This directory is a ROS package. If you want to use it in your own ROS environment, clone it into your catkin_ws/src
directory. Alternatively, if you use the development Docker-Compose setup, it will automatically be mounted as /home/reachy/catkin_ws/src/colab-reachy-ros
, and other packages associated with the Reachy will automatically be cloned.
- You must install ros noetic using the standard wiki procedure
- Then install other needed ROS packages with "sudo apt-get install -y ros-noetic-moveit ros-noetic-cv-camera"
- Then build your catikn_ws
- Navigate to the src folder in your catkin_ws, you'll need to clone three repos there:
git clone https://github.com/pollen-robotics/reachy_descriptioncd reachy_descriptiongit checkout -b ros1 a51b576cd ..git cloneFollow the instructions on https://github.com/pollen-robotics/reachy_moveit_config- git clone https://github.com/CircuitLaunch/colab_reachy_ros
- cd colab_reachy_ros
- pip3 install -r requirements.txt
- cd ..
- catkin_make
- source devel/setup.bash
- Open in your browser, and click connect once the unity window loads: https://playground.pollen-robotics.com/
- Run
roslaunch colab_reachy_ros moveit_demo.launch simulator:=true
- Open a new terminal to use the arm compliant mode service, and enter
rosservice call /right_arm_controller/set_arm_compliant False
this node controls the head of reachy its two servo motors which control the tilt and yaw of the head
TODO: add control of reachy's 2x antenna's (ears)
value="/dev/ttyACM0"/ must be changed to reflect the arduino your using
to find your arduino port run this command
1)
ls /dev/ttyACM*
2) if that doesnt work try to see if you see "arduino" in the name
ls /dev/serial/by-id
# run the node manually
## NOTE you must check that the arduino is plugged in and flashed, PLUS that you have the correct arduino port
roslaunch colab_reachy_ros head.launch
# single position (move tilt and yaw) debug statements
rostopic pub /head/position_animator/debug_point_degrees trajectory_msgs/JointTrajectoryPoint '{positions: [94, 100]}'
# Animation example
rostopic pub /head/position_animator_debug_degrees trajectory_msgs/JointTrajectory '{points:[{positions:[94,80]},{positions:[65,80]},{positions:[65,80]},{positions:[94,80]}]}'
rostopic pub /head/position_animator/debug_point_degrees trajectory_msgs/JointTrajectoryPoint '{positions: [0, 75]}'
- 2 hobby servo motors
Header header
string[] joint_names
JointTrajectoryPoint[] points <- im only using this one
example of a JointTrajectoryPoint
float64[] positions <- im only using this one
float64[] velocities
float64[] accelerations
float64[] effort
duration time_from_start
example if it was in json format
{
points:
[
{ positions: [1.5, 1.5] },
{ positions: [0.8, 1.2] },
{ positions: [0.7, 0.6] },
{ positions: [0.3, 0.1] }
]
}
rospy==1.15.9
sudo apt-get install ros-noetic-rosserial-arduino
sudo apt-get install ros-noetic-rosserial
---public topics---
"/head/position_animator_debug_degrees": JointTrajectory USE: sending a array of poses that make the head move in a animation
"/head/position_animator/debug_point_degrees" JointTrajectoryPoint USE: Use for sending just one position i use it to set the head to a location for testing
---private topics ---
"/head/position_animator": JointTrajectory UNUSED DO NOT USE
"/head/position_animator/debug_point": JointTrajectoryPoint UNUSED DO NOT USE
for debugging only private
"/head/neck_pan_goal": UInt16
"/head/neck_tilt_goal": UInt16
rostopic pub /head/position_animator/debug_point_degrees trajectory_msgs/JointTrajectoryPoint '{positions: [94, 100]}'
The arduino code has a manual offset of -90 to account for how the servo motors are mounted that can be changed to 0 if you dont have any offsets
94,80
94,115
94,80
94,115
94,80
rostopic pub /head/position_animator_debug_degrees trajectory_msgs/JointTrajectory '{points:[{positions:[94,80]},{positions:[94,115]},{positions:[94,80]},{positions:[94,115]},{positions:[94,80]}]}'
#### no guesture
```bash
94,80
65,80
115,80
65,80
115,80
94,80
rostopic pub /head/position_animator_debug_degrees trajectory_msgs/JointTrajectory '{points:[{positions:[94,80]},{positions:[65,80]},{positions:[115,80]},{positions:[65,80]},{positions:[115,80]},{positions:[94,80]}]}'
94,80
65,80
65,80
94,80
rostopic pub /head/position_animator_debug_degrees trajectory_msgs/JointTrajectory '{points:[{positions:[94,80]},{positions:[65,80]},{positions:[65,80]},{positions:[94,80]}]}'
94, 80
115,80
115,80
94, 80
rostopic pub /head/position_animator_debug_degrees trajectory_msgs/JointTrajectory '{points:[{positions:[94,80]},{positions:[115,80]},{positions:[115,80]},{positions:[94,80]}]}'
blah blah blah
echo foo
- foo
- bar
float64[] positions
float64[] velocities
float64[] accelerations
float64[] effort
duration time_from_start
requests==3.5.2
ls -hal
/EXAMPLE_TOPIC : Int16