9 Commits

Author SHA1 Message Date
  Binit Shah ebbae8da29
Update mkdocs_pt.yml 2 months ago
  Mohamed Fazil 4bb34277b7
Fix navigation_simple_commander.md fleet path 2 months ago
  Binit Shah 8f80a37d08
Update jogging.md 2 months ago
  Binit Shah 5d29c04891
Merge pull request #19 from hello-robot/docs/jogging 2 months ago
  Binit Shah 0059ad7df6
Update mkdocs_rt.yml 2 months ago
  Binit Shah 10204fb3d8
Update jogging.md 2 months ago
  Binit Shah 53d10b966b
Create jogging.md 2 months ago
  Binit Shah d0b76523fd
Fix log statement in aruco_tag_locator.py pt2 3 months ago
  Binit Shah 22b49e4934
Fix log statement in aruco_tag_locator.py 3 months ago
5 changed files with 114 additions and 5 deletions
Split View
  1. +1
    -0
      mkdocs_pt.yml
  2. +1
    -0
      mkdocs_rt.yml
  3. +3
    -3
      ros2/example_12.md
  4. +107
    -0
      ros2/jogging.md
  5. +2
    -2
      ros2/navigation_simple_commander.md

+ 1
- 0
mkdocs_pt.yml View File

@ -83,6 +83,7 @@ extra:
nav:
- ./moving.md
- Thread Safety: https://github.com/hello-robot/stretch_body/blob/master/docs/is_thread_safe/README.md
# - ./sensors.md # TODO
# - ./audio.md
# - ./pyfunmap.md

+ 1
- 0
mkdocs_rt.yml View File

@ -83,6 +83,7 @@ extra:
nav:
- Getting Started: ./getting_started.md
- Motion Commands: ./jogging.md
- Robot Drivers: ./robot_drivers.md
# - Writing Nodes: ./writing_nodes.md # TODO
- Navigation with Nav2:

+ 3
- 3
ros2/example_12.md View File

@ -209,7 +209,7 @@ class LocateArUcoTag(hm.HelloNode):
transform = self.tf_buffer.lookup_transform('base_link',
tag_name,
now)
self.get_logger().info("Found Requested Tag: \n%s", transform)
self.get_logger().info(f"Found Requested Tag: \n{transform}")
# Publish the transform
self.transform_pub.publish(transform)
@ -408,7 +408,7 @@ try:
transform = self.tf_buffer.lookup_transform('base_link',
tag_name,
now)
self.get_logger().info("Found Requested Tag: \n%s", transform)
self.get_logger().info(f"Found Requested Tag: \n{transform}")
self.transform_pub.publish(transform)
return transform
except TransformException as ex:
@ -455,4 +455,4 @@ def main():
node.destroy_node()
rclpy.shutdown()
```
Instantiate the `LocateArUcoTag()` object and run the `main()` method.
Instantiate the `LocateArUcoTag()` object and run the `main()` method.

+ 107
- 0
ros2/jogging.md View File

@ -0,0 +1,107 @@
# Motion Commands in ROS2
## Quickstart
Sending motion commands is as easy as:
1. Launch the ROS2 driver in a terminal:
```{.bash .shell-prompt .copy}
ros2 launch stretch_core stretch_driver.launch.py
```
2. Open iPython and type the following code, one line at a time:
```python
import hello_helpers.hello_misc as hm
node = hm.HelloNode.quick_create('temp')
node.move_to_pose({'joint_lift': 0.4}, blocking=True)
node.move_to_pose({'joint_wrist_yaw': 0.0, 'joint_wrist_roll': 0.0}, blocking=True)
```
## Writing a node
You can also write a ROS2 node to send motion commands:
```python
import hello_helpers.hello_misc as hm
class MyNode(hm.HelloNode):
def __init__(self):
hm.HelloNode.__init__(self)
def main(self):
hm.HelloNode.main(self, 'my_node', 'my_node', wait_for_first_pointcloud=False)
# my_node's main logic goes here
self.move_to_pose({'joint_lift': 0.6}, blocking=True)
self.move_to_pose({'joint_wrist_yaw': -1.0, 'joint_wrist_pitch': -1.0}, blocking=True)
node = MyNode()
node.main()
```
Copy the above into a file called "example.py" and run it using:
```{.bash .shell-prompt .copy}
python3 example.py
```
## Retrieving joint limits
In a terminal, echo the `/joint_limits` topic:
```{.bash .shell-prompt .copy}
ros2 topic echo /joint_limits
```
In a second terminal, request the driver publish the joint limits:
```{.bash .shell-prompt .copy}
ros2 service call /get_joint_states std_srvs/srv/Trigger {}
```
In the first terminal, you'll see a single message get published. It'll look like this:
```yaml
header:
stamp:
sec: 1725388967
nanosec: 818893747
frame_id: ''
name:
- joint_head_tilt
- joint_wrist_pitch
- joint_wrist_roll
- joint_wrist_yaw
- joint_head_pan
- joint_lift
- joint_arm
- gripper_aperture
- joint_gripper_finger_left
- joint_gripper_finger_right
position:
- -2.0171847360696185
- -1.5707963267948966
- -2.9114955354069467
- -1.3933658823294575
- -4.035903452927122
- 0.0
- 0.0
- -0.1285204486235414
- -0.3757907854489514
- -0.3757907854489514
velocity:
- 0.4908738521234052
- 0.45099035163837853
- 2.9176314585584895
- 4.416586351787409
- 1.7303303287350031
- 1.0966833704348709
- 0.5197662863936018
- 0.34289112948906764
- 1.0026056417808995
- 1.0026056417808995
effort: []
```
We're misusing the [sensor_msgs/JointState](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/JointState.html) message to publish the joint limits. The `name` array lists out each ranged joint. The `position` array lists the lower bound for each joint. The `velocity` array lists the upper bound. The length of these 3 arrays will be equal, because the index of the joint in the `name` array determines which index the corresponding limits will be in the other two arrays.
The revolute joints will have their limits published in radians, and the prismatic joints will have them published in meters. See the [Hardware Overview](../../getting_started/stretch_hardware_overview/) to see the ranges represented visually.

+ 2
- 2
ros2/navigation_simple_commander.md View File

@ -21,7 +21,7 @@ Let's set the patrol route up before you can execute this demo in your map. This
First, execute the following command while passing the correct map YAML. Then, press the 'Startup' button:
```{.bash .shell-prompt}
ros2 launch stretch_nav2 navigation.launch.py map:=${HELLO_ROBOT_FLEET}/maps/<map_name>.yaml
ros2 launch stretch_nav2 navigation.launch.py map:=${HELLO_FLEET_PATH}/maps/<map_name>.yaml
```
Since we expect the first point in the patrol route to be at the origin of the map, the first coordinates should be (0.0, 0.0). Next, to define the route, the easiest way to define the waypoints in the `security_route` array is by setting the robot at random locations in the map using the '2D Pose Estimate' button in RViz as shown below. For each location, note the x, and y coordinates in the position field of the base_footprint frame and add it to the `security_route` array in [simple_commander_demo.py](https://github.com/hello-robot/stretch_ros2/blob/humble/stretch_nav2/stretch_nav2/simple_commander_demo.py#L30).
@ -42,7 +42,7 @@ Go ahead and execute the following command to run the demo and visualize the res
Terminal 1:
```{.bash .shell-prompt}
ros2 launch stretch_nav2 demo_security.launch.py map:=${HELLO_ROBOT_FLEET}/maps/<map_name>.yaml
ros2 launch stretch_nav2 demo_security.launch.py map:=${HELLO_FLEET_PATH}/maps/<map_name>.yaml
```
<p align="center">

Loading…
Cancel
Save