Only released in EOL distros:  

arm_navigation: collision_free_arm_trajectory_controller | move_arm | move_arm_head_monitor | move_arm_msgs

Package Summary

The move_arm package provides an implementation of a action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a robot arm. The move_arm node links together a planner, trajectory monitor and trajectory controller to acheive its goal. It supports any planner that provides a GetMotionPlan interface and any controller that provides services for setting, querying and canceling trajectories. The node is designed to be modular and so uses ROS services for planning, control and IK and does minimal computation within the node itself.

arm_navigation: arm_kinematics_constraint_aware | arm_navigation_msgs | collision_map | collision_space | constraint_aware_spline_smoother | geometric_shapes | joint_normalization_filters | kinematics_base | kinematics_msgs | mapping_rviz_plugin | motion_planning_rviz_plugin | move_arm | ompl | ompl_ros_interface | planning_environment | planning_models | robot_self_filter | sbpl | spline_smoother | trajectory_filter_server

Package Summary

The move_arm package provides an implementation of a action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a robot arm. The move_arm node links together a planner, trajectory monitor and trajectory controller to acheive its goal. It supports any planner that provides a GetMotionPlan interface and any controller that provides services for setting, querying and canceling trajectories. The node is designed to be modular and so uses ROS services for planning, control and IK and does minimal computation within the node itself.

arm_navigation: arm_kinematics_constraint_aware | arm_navigation_msgs | collision_map | collision_space | constraint_aware_spline_smoother | geometric_shapes | joint_normalization_filters | kinematics_base | kinematics_msgs | mapping_rviz_plugin | motion_planning_rviz_plugin | move_arm | ompl_ros_interface | planning_environment | planning_models | robot_self_filter | spline_smoother | trajectory_filter_server

Package Summary

The move_arm package provides an implementation of a action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a robot arm. The move_arm node links together a planner, trajectory monitor and trajectory controller to acheive its goal. It supports any planner that provides a GetMotionPlan interface and any controller that provides services for setting, querying and canceling trajectories. The node is designed to be modular and so uses ROS services for planning, control and IK and does minimal computation within the node itself.

arm_navigation: arm_kinematics_constraint_aware | arm_navigation_msgs | collision_map | collision_space | constraint_aware_spline_smoother | geometric_shapes | joint_normalization_filters | kinematics_base | kinematics_msgs | mapping_rviz_plugin | motion_planning_rviz_plugin | move_arm | ompl_ros_interface | planning_environment | planning_models | robot_self_filter | spline_smoother | trajectory_filter_server

Package Summary

The move_arm package provides an implementation of a action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a robot arm. The move_arm node links together a planner, trajectory monitor and trajectory controller to acheive its goal. It supports any planner that provides a GetMotionPlan interface and any controller that provides services for setting, querying and canceling trajectories. The node is designed to be modular and so uses ROS services for planning, control and IK and does minimal computation within the node itself.

ROS API

This package provides the move_arm node which is a major component of the arm navigation stack. The node uses ROS services to connect to an environment server for most of its internal needs: e.g. checking trajectories and states for collisions, performing inverse kinematics, talking to controllers, etc.. It communicates with users using an action interface.

API Stability

  • The ROS API is REVIEWED but UNSTABLE

ROS Parameters

Parameters

~move_arm_frequency (double, default: 50.0)
  • The rate in Hz at which to run the internal state loop for move_arm. This is also the rate at which move_arm will monitor the execution of the planned trajectory.
~group (string, default: "")
  • The name of the group on which move_arm is acting. A group is a collection of joints (and corresponding links). Groups are specified using a yaml file. See planning environment YAML configuration for more details on how to specify groups.
~ik_allowed_time (double, default: 2.0)
  • The time in seconds that is allowed for IK computation. Move arm will pass this parameter in a service request to the IK node.
~trajectory_filter_allowed_time (double, default: 2.0)
  • The time in seconds that is allowed for trajectory filtering. Move arm will pass this parameter in a service request to the trajectory filter server.
~controller_action_name (string, default: /r_arm_controller/joint_trajectory_action/)
  • Move arm interfaces to controllers through a simple action client. This parameter specifies the name of the action server corresponding to the controller.

Action API

The move_arm node provides an implementation of a SimpleActionServer (see actionlib documentation), that takes in goals containing move_arm/MoveArmGoal messages. You can communicate with the move_arm node over ROS directly, but the recommended way to send goals to move_arm if you care about tracking their status is by using the SimpleActionClient. Please see actionlib documentation for more information.

Action Subscribed Topics

move_arm/goal (move_arm_msgs/MoveArmGoal)

  • A goal for move_arm to pursue in the world.
move_arm/cancel (actionlib_msgs/GoalID)
  • A request to cancel a specific goal.

Action Published Topics

move_arm/feedback (move_arm_msgs/MoveArmFeedback)

  • Feedback contains two fields: (a) the current state that the internal move arm state machine is in, (b) time to completion
move_arm/status (actionlib_msgs/GoalStatusArray)
  • Provides status information on the goals that are sent to the move_arm action.
move_arm/result (move_arm_msgs/MoveArmActionResult)
  • It contains an error code that indicates why move arm failed. The error code is of type motion_planning_msgs/ArmNavigationErrorCodes.

move_arm required services

Move arm uses service calls to get information about the robot and the world, compute IK, call planners and do control. It performs minimal computation within the node itself. The service calls are presented below categorized according to the type of service they provide.

Services

Utility services
These are the services that move_arm uses to perform utility functions like figuring out all the joints in a group.
get_joints_in_group (planning_environment_msgs/GetJointsInGroup)
  • This service allows move_arm to find out which joints belong in a particular group (collection of joints). E.g., the group right_arm contains the joints: r_shoulder_pan_joint r_shoulder_lift_joint r_upper_arm_roll_joint r_elbow_flex_joint r_forearm_roll_joint r_wrist_flex_joint r_wrist_roll_joint
get_robot_state (planning_environment_msgs/GetRobotState)
  • This services allows move_arm to get the complete state of the robot as a motion_planning_msgs/RobotState message. This message contains information about the joint positions of all the (real) joints on the robot.
Monitoring/Checking services
These are the services that move_arm uses to monitor the environment, check the plan that it receives, check whether a goal state has been reached and monitor the safety of a executed trajectory
get_environment_safety (planning_environment_msgs/GetEnvironmentSafety)
  • This service allows move_arm to determine if the environment is safe for a plan to be generated. This service could be used, for example, to warn the move_arm node that state message have not been received from the robot in a while or that sensor messages are outdated and so information about the environment is invalid.
get_execution_safety (planning_environment_msgs/GetJointTrajectoryValidity)
  • This services allows move_arm to determine if the execution of the trajectory is safe. The server node checks for collisions along the part of the trajectory that is yet to be traversed. Internally, it computes the closest state on the trajectory to the current state of the robot and uses this state to compute the part of the trajectory that it still needs to check.
get_trajectory_validity (planning_environment_msgs/GetJointTrajectoryValidity)
  • Check if the specified plan is valid, i.e. whether it satisfies the goal and path constraints AND is not in collision at any point along the path.
IK service
This service allows move_arm to perform inverse kinematics on a particular link on the robot using a particular set of joints
arm_ik (kinematics_msgs/GetConstraintAwarePositionIK)
  • The service contains the name of the link to perform IK for and the set of joints that should be used in the IK computation.
Planning service
This is the service that move_arm uses to call a planner to compute motion plans
(motion_planning_msgs/GetMotionPlan)
  • The service name is set as part of the MoveArmGoal message. In addition, when the actual service call is made, the service name is prepended with the planner_id field provided in the MoveArmGoal message.
Filtering service
This is the service that move_arm uses to filter paths before sending them out to the controller
filter_trajectory (motion_planning_msgs/FilterJointTrajectoryWithConstraints)
  • Move arm uses this service to filter trajectories.

move_arm topics

Visualization topics
These are the topics on which move_arm publishes the planned path and the desired joint goal
display_joint_goal (motion_planning_msgs/DisplayTrajectory)
  • The desired joint goal that move_arm is trying to move the arm to.
display_path (motion_planning_msgs/DisplayTrajectory)
  • The planned path that move_arm will move the arm along.
allowed_contact_regions_array (visualization_msgs/MarkerArray)
  • This is a visual representation of the allowed contacts regions. The allowed contacts regions are regions in space where certain links of the robot may be allowed to touch objects. They are specified by a user within the MoveArmGoal message.

Additional Configuration Details

Additional configuration details are provided on the Configuration page.

Wiki: move_arm (last edited 2010-10-14 00:15:24 by KenConley)