diff --git a/README.md b/README.md index 8bd8a70ad11e43bb8f5a0f2b4c556bb152696127..a116d4525d9454549cc64ec3d4cf6e341b4b706a 100644 --- a/README.md +++ b/README.md @@ -141,65 +141,65 @@ It provides a Simple Condition for each module status. The name of each Simple C ### Subscribed topics -- */joint_states* ([sensor_msgs/JointState](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/JointState.html)): +- *~/joint_states* ([sensor_msgs/JointState](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/JointState.html)): The servos' current postions. If no joint_states is received the module return a no_joint_states status. ### Parameters -- **frame_id** *(String; Default:joints_module)*: +- **~/frame_id** *(String; Default:joints_module)*: The frame ID. -- **rate_hz** *(Double; Default: 1.0; Max: 100.0; Min: 1.0)*: +- **~/rate_hz** *(Double; Default: 1.0; Max: 100.0; Min: 1.0)*: Joints module rate in Hz. ##### PointTo -The usual ActionModule parameters named as *pt_\<ActionModule_parameter\>* and: +The usual ActionModule parameters named as *~/pt_\<ActionModule_parameter\>* and: -- **pointing_frame** *(String; Default:)*: +- **~/pointing_frame** *(String; Default:)*: The pointing frame. -- **pointing_axis** *(Integer; Default: 2; Max: 2; Min: 0)*: +- **~/pointing_axis** *(Integer; Default: 2; Max: 2; Min: 0)*: The pointing axis (X=0, Y=1, Z=2). -- **point_frame** *(String; Default:)*: +- **~/point_frame** *(String; Default:)*: The point's frame. -- **pt_enabled** *(Bool; Default: True)*: +- **~/pt_enabled** *(Bool; Default: True)*: Enable pointTo action execution. ##### PointToTracker -The usual ActionModule parameters named as *tracker_\<ActionModule_parameter\>* and: +The usual ActionModule parameters named as *~/tracker_\<ActionModule_parameter\>* and: -- **tracker_enabled** *(Bool; Default: True)*: +- **~/tracker_enabled** *(Bool; Default: True)*: Enable pointTo tracker action execution. ##### MoveToAngles -The usual ActionModule parameters named as *move_to_angles_\<ActionModule_parameter\>* and: +The usual ActionModule parameters named as *~/move_to_angles_\<ActionModule_parameter\>* and: -- **move_to_angles_time_from_start** *(Integer; Default: 10; Max: 100; Min: 0)*: +- **~/move_to_angles_time_from_start** *(Integer; Default: 10; Max: 100; Min: 0)*: Max time in seconds to finish the action. -- **move_to_angles_pos_tol** *(Double; Default: 0.02; Min: -1.0)*: +- **~/move_to_angles_pos_tol** *(Double; Default: 0.02; Min: -1.0)*: Path and goal position tolerance in rad or m. -- **move_to_angles_vel_tol** *(Double; Default: 0.0; Min: -1.0)*: +- **~/move_to_angles_vel_tol** *(Double; Default: 0.0; Min: -1.0)*: Path and goal velocity tolerance in rad/s or m/s. -- **move_to_angles_acc_tol** *(Double; Default: 0.0; Min: -1.0)*: +- **~/move_to_angles_acc_tol** *(Double; Default: 0.0; Min: -1.0)*: Path and goal acceleration tolerance in rad/s² or m/s². -- **move_to_angles_time_tol** *(Double; Default: 0.1; Max: 1.0; Min: 0.0)*: +- **~/move_to_angles_time_tol** *(Double; Default: 0.1; Max: 1.0; Min: 0.0)*: Path and goal time tolerance in percentaje. -- **move_to_angles_enabled** *(Bool; Default: True)*: +- **~/move_to_angles_enabled** *(Bool; Default: True)*: Enable move to angles action execution ##### JointStates -The usual WatchDog parameters named as *joint_states_\<WatchDog_parameter\>*. +The usual WatchDog parameters named as *~/joint_states_\<WatchDog_parameter\>*. # Dependencies