You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

151 lines
7.3 KiB

3 years ago
  1. ![](../images/banner.png)
  2. ## Overview
  3. *hello_helpers* mostly consists of the hello_helpers Python module. This module provides various Python files used across stretch_ros that have not attained sufficient status to stand on their own.
  4. ## Capabilities
  5. *fit_plane.py* : Fits planes to 3D data.
  6. *hello_misc.py* : Various functions, including a helpful Python object with which to create ROS nodes.
  7. *hello_ros_viz.py* : Various helper functions for vizualizations using RViz.
  8. ## Typical Usage
  9. ```python
  10. import hello_helpers.fit_plane as fp
  11. ```
  12. ```python
  13. import hello_helpers.hello_misc as hm
  14. ```
  15. ```python
  16. import hello_helpers.hello_ros_viz as hr
  17. ```
  18. # API
  19. ## Classes
  20. ### [HelloNode](./src/hello_helpers/hello_misc.py)
  21. This class is a convenience class for creating a ROS node for Stretch. The most common way to use this class is to extend it. In your extending class, the main funcion would call `HelloNode`'s main function. This would look like:
  22. ```python
  23. import hello_helpers.hello_misc as hm
  24. class MyNode(hm.HelloNode):
  25. def __init__(self):
  26. hm.HelloNode.__init__(self)
  27. def main(self):
  28. hm.HelloNode.main(self, 'my_node', 'my_node', wait_for_first_pointcloud=False)
  29. # my_node's main logic goes here
  30. node = MyNode()
  31. node.main()
  32. ```
  33. There is also a one-liner class method for instantiating a `HelloNode` for easy prototyping. One example where this is handy is sending pose commands from iPython:
  34. ```python
  35. # roslaunch the stretch launch file beforehand
  36. import hello_helpers.hello_misc as hm
  37. temp = hm.HelloNode.quick_create('temp')
  38. temp.move_to_pose({'joint_lift': 0.4})
  39. ```
  40. #### Methods
  41. ##### `move_to_pose(pose, return_before_done=False, custom_contact_thresholds=False, custom_full_goal=False)`
  42. This method takes in a dictionary that describes a desired pose for the robot and communicates with [stretch_driver](../stretch_core/README.md#stretchdrivernodesstretchdriver) to execute it. The basic format of this dictionary is string/number key/value pairs, where the keys are joint names and the values are desired position goals. For example, `{'joint_lift': 0.5}` would put the lift at 0.5m in its joint range. A full list of command-able joints is published to the `/stretch/joint_states` topic. Used within a node extending `HelloNode`, calling this method would look like:
  43. ```python
  44. self.move_to_pose({'joint_lift': 0.5})
  45. ```
  46. Internally, this dictionary is converted into a [FollowJointTrajectoryGoal](http://docs.ros.org/en/diamondback/api/control_msgs/html/msg/FollowJointTrajectoryGoal.html) that is sent to a [FollowJointTrajectory action](http://docs.ros.org/en/noetic/api/control_msgs/html/action/FollowJointTrajectory.html) server in stretch_driver. This method waits by default for the server to report that the goal has completed executing. However, you can return before the goal has completed by setting the `return_before_done` argument to True. This can be useful for preempting goals.
  47. There are two additional arguments that enable you to customize how the pose is executed. If you set `custom_contact_thresholds` to True, this method expects a different format dictionary: string/tuple key/value pairs, where the keys are still joint names, but the values are `(position_goal, effort_threshold)`. The addition of a effort threshold enables you to detect when a joint has made contact with something in the environment, which is useful for manipulation or safe movements. For example, `{'joint_arm': (0.5, 20)}` commands the telescoping arm fully out (the arm is nearly fully extended at 0.5 meters) but with a low enough effort threshold (20% of the arm motor's max effort) that the motor will stop when the end of arm has made contact with something. Again, in a node, this would look like:
  48. ```python
  49. self.move_to_pose({'joint_arm': (0.5, 40)}, custom_contact_thresholds=True)
  50. ```
  51. If you set `custom_full_goal` to True, the dictionary format is string/tuple key/value pairs, where keys are joint names again, but values are `(position_goal, velocity, acceleration, effort_threshold)`. The velocity and acceleration components allow you to customize the trajectory profile the joint follows while moving to the goal position. In the following example, the arm telescopes out slowly until contact is detected:
  52. ```python
  53. self.move_to_pose({'joint_arm': (0.5, 0.01, 0.01, 40)}, custom_full_goal=True)
  54. ```
  55. ##### `get_tf(from_frame, to_frame)`
  56. Use this method to get the transform ([geometry_msgs/TransformStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/TransformStamped.html)) between two frames. This method is blocking. For example, this method can do forward kinematics from the base_link to the link between the gripper fingers, link_grasp_center, using:
  57. ```python
  58. # roslaunch the stretch launch file beforehand
  59. import rospy
  60. import hello_helpers.hello_misc as hm
  61. temp = hm.HelloNode.quick_create('temp')
  62. t = temp.get_tf('base_link', 'link_grasp_center')
  63. print(t.transform.translation)
  64. ```
  65. ##### `get_robot_floor_pose_xya(floor_frame='odom')`
  66. Returns the current estimated x, y position and angle of the robot on the floor. This is typically called with respect to the odom frame or the map frame. x and y are in meters and the angle is in radians.
  67. ##### `main(node_name, node_topic_namespace, wait_for_first_pointcloud=True)`
  68. When extending the `HelloNode` class, call this method at the very beginning of your `main()` method. This method handles setting up a few ROS components, including registering the node with the ROS server, creating a TF listener, creating a [FollowJointTrajectory](http://docs.ros.org/en/noetic/api/control_msgs/html/action/FollowJointTrajectory.html) client for the [`move_to_pose()`](#movetoposepose-returnbeforedonefalse-customcontactthresholdsfalse-customfullgoalfalse) method, subscribing to depth camera point cloud topic, and connecting to the quick-stop service.
  69. Since it takes up to 30 seconds for the head camera to start streaming data, the `wait_for_first_pointcloud` argument will get the node to wait until it has seen camera data, which is helpful if your node is processing camera data.
  70. ##### `quick_create(name, wait_for_first_pointcloud=False)`
  71. A class level method for quick testing. This allows you to avoid having to extend `HelloNode` to use it.
  72. ```python
  73. # roslaunch the stretch launch file beforehand
  74. import hello_helpers.hello_misc as hm
  75. temp = hm.HelloNode.quick_create('temp')
  76. temp.move_to_pose({'joint_lift': 0.4})
  77. ```
  78. #### Subscribed Topics
  79. ##### /camera/depth/color/points ([sensor_msgs/PointCloud2](http://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/PointCloud2.html))
  80. Provides a point cloud as currently seen by the Realsense depth camera in Stretch's head. Accessible from the `self.point_cloud` attribute.
  81. ```python
  82. # roslaunch the stretch launch file beforehand
  83. import hello_helpers.hello_misc as hm
  84. temp = hm.HelloNode.quick_create('temp', wait_for_first_pointcloud=True)
  85. print(temp.point_cloud)
  86. ```
  87. #### Subscribed Services
  88. ##### /stop_the_robot ([std_srvs/Trigger](https://docs.ros.org/en/noetic/api/std_srvs/html/srv/Trigger.html))
  89. Provides a service to quickly stop any motion currently executing on the robot.
  90. ```python
  91. # roslaunch the stretch launch file beforehand
  92. from std_srvs.srv import TriggerRequest
  93. import hello_helpers.hello_misc as hm
  94. temp = hm.HelloNode.quick_create('temp')
  95. temp.stop_the_robot_service(TriggerRequest())
  96. ```
  97. ## License
  98. For license information, please see the LICENSE files.