The iPython interpreter also allows you to execute blocks of code in a single go instead of running commands line by line. To end the interpreter session, type exit() and press enter.
## Change Credentials
Finally, we recommend that you change the login credentials for the default user, hello-robot.
The iPython interpreter also allows you to execute blocks of code in a single go instead of running commands line by line. To end the interpreter session, type exit() and press enter.
@ -71,7 +71,7 @@ The third child of the root node is the `Move to dock` action node. This is a si
The fourth and final child of the sequence node is another `fallback` node with two children - the `Charging?` condition node and the `Move to predock` action node with an `inverter` decorator node (+/- sign). The `Charging?` condition node is a subscriber that checks if the 'present' attribute of the `BatteryState` message is True. If the robot has backed up correctly into the docking station and the charger port latched, this node should return SUCCESS and the autodocking would succeed. If not, the robot moves back to the predock pose through the `Move to predock` action node and tries again.
## Code Breakdown
Let's jump into the code to see how things work under the hood. Follow along [here]() (TODO after merge) to have a look at the entire script.
Let's jump into the code to see how things work under the hood. Follow along [here](https://github.com/hello-robot/stretch_ros/blob/noetic/stretch_demos/nodes/autodocking_bt.py) to have a look at the entire script.
We start off by importing the dependencies. The ones of interest are those relating to py-trees and the various behaviour classes in autodocking.autodocking_behaviours, namely, MoveBaseActionClient, CheckTF and VisualServoing. We also created custom ROS action messages for the ArucoHeadScan action defined in the action directory of stretch_demos package.
@ -172,7 +172,7 @@ The next line, `rospy.init_node(NAME, ...)`, is very important as it tells rospy
Instantiate class with `Balloon()`.
Give control to ROS with `rospy.spin()`. This will allow the callback to be called whenever new messages come in. If we don't put this line in, then the node will not work, and ROS will not process any messages.
The `rospy.rate()` is the rate at which the node is going to publish information (10 Hz).
Set `trajectory_goal` as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` set by your list of points. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
Set `trajectory_goal` as a `FollowJointTrajectoryGoal` and define the joint names as a list. Then `trajectory_goal.trajectory.points` set by your list of points. Specify the coordinate frame that we want (*base_link*) and set the time to be now.
@ -84,7 +84,7 @@ The joint_states_callback is the callback method that receives the most recent j
self.joint_state = joint_state
```
The copute_difference() method is where we call the get_transform() method from the FrameListener class to compute the difference between the base_link and base_right frame with an offset of 0.5 m in the negative y-axis.
The compute_difference() method is where we call the get_transform() method from the FrameListener class to compute the difference between the base_link and base_right frame with an offset of 0.5 m in the negative y-axis.
@ -103,7 +103,7 @@ To compute the (x, y) coordinates of the SE2 pose goal, we compute the transform
base_position_y = P_base[1, 0]
```
From this, it is relatively straightforward to compute the angle phi and the euclidean distance dist. We then compute the angle z_rot_base to perform the last angle correction.
From this, it is relatively straightforward to compute the angle **phi** and the euclidean distance **dist**. We then compute the angle z_rot_base to perform the last angle correction.
Ain't that something! If you followed the breakdown in object detection, you'll find that the only change if you are looking to detect faces, facial landmarks or estimat head pose instead of detecting objects is in using a different deep learning model that does just that. For this, we will explore how to use the OpenVINO toolkit. Let's head to the detect_faces.py [node](https://github.com/hello-robot/stretch_ros2/blob/galactic/stretch_deep_perception/stretch_deep_perception/detect_faces.py) to begin.
Ain't that something! If you followed the breakdown in object detection, you'll find that the only change if you are looking to detect faces, facial landmarks or estimate head pose instead of detecting objects is in using a different deep learning model that does just that. For this, we will explore how to use the OpenVINO toolkit. Let's head to the detect_faces.py [node](https://github.com/hello-robot/stretch_ros2/blob/galactic/stretch_deep_perception/stretch_deep_perception/detect_faces.py) to begin.
In the main() method, we see a similar structure as with the object detction node. We first create an instance of the detector using the HeadPoseEstimator class from the [head_estimator.py](https://github.com/hello-robot/stretch_ros2/blob/galactic/stretch_deep_perception/stretch_deep_perception/head_estimator.py) script to configure the deep learning models. Next, we pass this to an instance of the DetectionNode class from the detection_node.py script and call the main function.
**OPTIONAL**: If you would like to see how the static frames update while the robot is in motion, run the stow command node and observe the tf frames in RViz.
@ -35,9 +35,8 @@ The GIF below visualizes what happens when running the previous node.
Then run the tf2 broadcaster node to create the three static frames.
```{.bash .shell-prompt}
ros2 run stretch_ros_tutorials tf2_broadcaster
ros2 run stretch_ros_tutorials tf_broadcaster
```
Finally, run the tf2 listener node to print the transform between two links.
```{.bash .shell-prompt}
ros2 run stretch_ros_tutorials tf2_listener
ros2 run stretch_ros_tutorials tf_listener
```
Within the terminal the transform will be printed every 1 second. Below is an example of what will be printed in the terminal. There is also an image for reference of the two frames.
@ -59,9 +59,11 @@ ros2 run stretch_ros_tutorials scan_filter
Then run the following command to bring up a simple RViz configuration of the Stretch robot.
```{.bash .shell-prompt}
ros2 run rviz2 rviz2 -d `ros2 pkg prefix stretch_calibration`/rviz/stretch_simple_test.rviz
ros2 run rviz2 rviz2 -d `ros2 pkg prefix stretch_calibration`/share/stretch_calibration/rviz/stretch_simple_test.rviz
```
!!! note
If the laser scan points published by the scan or the scan_filtered topic are not visible in RViz, you can visualize them by adding them using the 'Add' button in the left panel, selecting the 'By topic' tab, and then selecting the scan or scan_filtered topic.
Change the topic name from the LaserScan display from */scan* to */filter_scan*.
ROS 2 tutorials are still under active development.
ROS 2 tutorials are still under active development. For this exercise you'll need to have Ubuntu 22.04 and ROS Iron for it to work completly.
Stretch driver offers a [`FollowJointTrajectory`](http://docs.ros.org/en/api/control_msgs/html/action/FollowJointTrajectory.html) action service for its arm. Within this tutorial, we will have a simple FollowJointTrajectory command sent to a Stretch robot to execute.
@ -22,13 +22,13 @@ We will disable ROS1 by commenting out the ROS1 related lines by adding '#' in f
Save this configuration using **Ctrl + S**. Close out of the current terminal and open a new one. ROS2 is now enabled!
## Refreshing the ROS2 workspace
While Stretch ROS2 is in beta, there will be frequent updates to the ROS2 software. Therefore, it makes sense to refresh the ROS2 software to the latest available release. In the ROS and ROS2 world, software is organized into "ROS Workspaces", where packages can be developed, compiled, and be made available to run from the command line. We are going to refresh the ROS2 workspace, which is called "~/ament_ws" and available in the home directory. Follow the [Create a new ROS Workspace guide](https://docs.hello-robot.com/0.2/stretch-install/docs/ros_workspace/) to run the `stretch_create_ament_workspace.sh` script. This will delete the existing "~/ament_ws", create a new one with all of the required ROS2 packages for Stretch, and compile it.
While Stretch ROS2 is in beta, there will be frequent updates to the ROS2 software. Therefore, it makes sense to refresh the ROS2 software to the latest available release. In the ROS and ROS2 world, software is organized into "ROS Workspaces", where packages can be developed, compiled, and be made available to run from the command line. We are going to refresh the ROS2 workspace, which is called "~/ament_ws" and available in the home directory. Follow the [Create a new ROS Workspace guide](https://docs.hello-robot.com/0.2/stretch-install/docs/ros_workspace/) to run the `stretch_create_ament_workspace.sh` script. This will delete the existing "~/ament_ws", create a new one with all of the required ROS2 packages for Stretch, and compile it. Also we need to take into account that building the workspace is different in ROS2, we need to type colcon build instead of catkin make for it to work.
## Testing Keyboard Teleop
We can test whether the ROS2 workspace was enabled successfully by testing out the ROS2 drivers package, called "stretch_core", with keyboard teleop. In one terminal, we'll launch Stretch's ROS2 drivers using:
The graph allows a user to observe and affirm if topics are broadcasted to the correct nodes. This method can also be utilized to debug communication issues.
The Stretch robot is equipped with the [Intel RealSense D435i camera](https://www.intelrealsense.com/depth-camera-d435i/), an essential component that allows the robot to measure and analyze the world around it. In this tutorial, we are going to showcase how to visualize the various topics published by the camera.
Begin by running the stretch `driver.launch.py` file.
```{.bash .shell-prompt}
ros2 launch stretch_core stretch_driver.launch.py
```
To activate the [RealSense camera](https://www.intelrealsense.com/depth-camera-d435i/) and publish topics to be visualized, run the following launch file in a new terminal.
Within this tutorial package, there is an [RViz config file](https://github.com/hello-robot/stretch_tutorials/blob/noetic/rviz/perception_example.rviz) with the topics for perception already in the Display tree. You can visualize these topics and the robot model by running the command below in a new terminal.
```{.bash .shell-prompt}
ros2 run rviz2 rviz2 -d /home/hello-robot/ament_ws/src/stretch_tutorials/rviz/perception_example.rviz
```
### PointCloud2 Display
A list of displays on the left side of the interface can visualize the camera data. Each display has its properties and status that notify a user if topic messages are received.
For the `PointCloud2` display, a [sensor_msgs/pointCloud2](http://docs.ros.org/en/lunar/api/sensor_msgs/html/msg/PointCloud2.html) message named `/camera/depth/color/points` is received and the GIF below demonstrates the various display properties when visualizing the data.
The `Image` display when toggled creates a new rendering window that visualizes a [sensor_msgs/Image](http://docs.ros.org/en/lunar/api/sensor_msgs/html/msg/Image.html) messaged, */camera/color/image_raw*. This feature shows the image data from the camera; however, the image comes out sideways.
The `DepthCloud` display is visualized in the main RViz window. This display takes in the depth image and RGB image provided by RealSense to visualize and register a point cloud.
Hello Robot also has a ROS package that uses deep learning models for various detection demos. A link to the tutorials is provided: [stretch_deep_perception](https://docs.hello-robot.com/0.2/stretch-tutorials/ros2/deep_perception/).
[Dynamixel ID:011] ping Succeeded. Dynamixel model number : 1080
[Dynamixel ID:011] ping Succeeded. Dynamixel model number : 1080. Baud 115200
------ MENU -------
m: menu
a: increment position 50 tick
@ -52,6 +52,10 @@ t: set max temp
i: set id
d: disable torque
e: enable torque
x: put in multi-turn mode
y: put in position mode
w: put in pwm mode
f: put in vel mode
-------------------
```
@ -67,12 +71,14 @@ Output:
```{.bash .no-copy}
For use with S T R E T C H (TM) RESEARCH EDITION from Hello Robot Inc.
Rebooting: head_pan
[Dynamixel ID:011] Reboot Succeeded.
Rebooting: head_tilt
[Dynamixel ID:012] Reboot Succeeded.
[Dynamixel ID:013] Reboot Succeeded.
Rebooting: stretch_gripper
[Dynamixel ID:014] Reboot Succeeded.
Rebooting: wrist_yaw
[Dynamixel ID:013] Reboot Succeeded.
```
### Identify Servos on the Bus
@ -80,38 +86,42 @@ For use with S T R E T C H (TM) RESEARCH EDITION from Hello Robot Inc.
If it is unclear which servos are on the bus, and at what baud rate, you can use the `REx_dynamixel_id_scan.py` tool. Here we see that the two head servos are at ID `11` and `12` at baud `57600`.
Identified current baud of 57600. Changing baud to 115200
Success at changing baud
Success at changing baud. Current baud is 115200 for servo 13 on bus /dev/hello-dynamixel-wrist
```
!!! note
@ -139,15 +147,15 @@ Success at changing baud
Dynamixel servos come with `ID=1` from the factory. When adding your servos to the end-of-arm tool, you may want to set the servo ID using the `REx_dynamixel_id_change.py` tool. For example:
@ -95,24 +95,35 @@ Parameters may be named with a suffix to help describe the unit type. For exampl
### The Robot Status
The Robot derives from the [Device class](https://github.com/hello-robot/stretch_body/blob/master/body/stretch_body/device.py). It also encapsulates several other Devices:
The Robot derives from the [Device class](https://github.com/hello-robot/stretch_body/blob/master/body/stretch_body/device.py) and we have subclasses that derives from this Device class such as the [Prismatic Joint](https://github.com/hello-robot/stretch_body/blob/master/body/stretch_body/prismatic_joint.py) and the [Dynamixel XL460](https://github.com/hello-robot/stretch_body/blob/master/body/stretch_body/dynamixel_hello_XL430.py). It also encapsulates several other Devices:
All devices contain a Status dictionary. The Status contains the most recent sensor and state data of that device. For example, looking at the Arm class we see:
```python
class Arm(Device):
def __init__(self):
class Arm(PrismaticJoint):
def __init__(self,usb=None):
```
As we can see the arm class is part of the PrismaticJoint class but this is also part of the Device class as we can see here:
The Status dictionaries are automatically updated by a background thread of the Robot class at around 25Hz. The Status data can be accessed via the Robot class as below:
@ -189,4 +200,4 @@ robot.stop()
The Dynamixel servos do not use the Hello Robot communication protocol. As such, the head, wrist, and gripper will move immediately upon issuing a motion command.
------
<divalign="center"> All materials are Copyright 2022 by Hello Robot Inc. Hello Robot and Stretch are registered trademarks.</div>
<divalign="center"> All materials are Copyright 2022 by Hello Robot Inc. Hello Robot and Stretch are registered trademarks.</div>
@ -61,6 +61,7 @@ Programming a splined trajectory is straightforward. For example, try the follow
import stretch_body.robot
r=stretch_body.robot.Robot()
r.startup()
#r.arm.motor.disable_sync_mode() **If you want to try running the code with this command you'll need to coment the r.push_command() and it will work as well
#Define the waypoints
times = [0.0, 10.0, 20.0]
@ -73,6 +74,8 @@ for waypoint in zip(times, positions, velocities):
#Begin execution
r.arm.follow_trajectory()
r.push_command()
time.sleep(0.1)
#Wait unti completion
while r.arm.is_trajectory_active():
@ -87,7 +90,7 @@ This will cause the arm to move from its current position to 0.45m, then back to
* This will execute a Cubic spline as we did not pass in accelerations to in `r.arm.trajectory.add`
* The call to `r.arm.follow_trajectory` is non-blocking and the trajectory generation is handled by a background thread of the Robot class
If you're interested in exploring the trajectory API further the [code for the `stretch_trajectory_jog.py`](https://github.com/hello-robot/stretch_body/blob/master/tools/bin/stretch_trajectory_jog.py) is a great reference to get started.
If you're interested in exploring the trajectory API further. the [code for the `stretch_trajectory_jog.py`](https://github.com/hello-robot/stretch_body/blob/master/tools/bin/stretch_trajectory_jog.py) is a great reference to get started.