Only released in EOL distros:  

Newly proposed, mistyped, or obsolete package. Could not find package "simple_arm_server" in rosdoc: /var/www/docs.ros.org/en/api/simple_arm_server/manifest.yaml

Node API

The simple_arm_server package contains a single node, simple_arm_server.py which offers an action-based interface. This server can generate joint trajectories for 4 and 5 DOF arms using the arm_kinematics package for IK. It transparently handles the issues of low-dof manipulators being unable to reach all 6-dof poses.

The output of the simple_arm_server uses the same action-based interface as arm_navigation. The simple_arm_server does not do collision avoidance, if you are looking for collision avoidance planning please see move_arm

ROS Parameters

~arm_dof (int, default: 5)

  • Number of servos in the arm chain between root and tip (not including gripper).
~root_name (str, default: base_link)
  • Name of frame that arm is rooted at.
~tip_name (str, default: gripper_link)
  • Name of frame that gripper tip is at.
~timeout (float, default: 5.0)
  • Maximum amount of time to wait for IK solution.

Action API

The simple_arm_server.py node provides an implementation of a SimpleActionServer (see actionlib documentation), that takes in goals containing simple_arm_server/MoveArmGoal messages. You can communicate with the simple_arm_server node over ROS directly, but the recommended way to send goals to simple_arm_server 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 (simple_arm_server/MoveArmGoal)

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

Action Published Topics

move_arm/feedback (simple_arm_server/MoveArmFeedback)

  • Feedback contains the estimated 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 (simple_arm_server/MoveArmActionResult)
  • Provides boolean status of success or failure.

Other Subscriptions

joint_states (sensor_msgs/JointStates)

  • Used to seed the IK solver.

Required Services

arm_kinematics/get_ik (kinematics_msgs/GetPositionIK)

  • Used to get IK solution.
arm_kinematics/get_ik_solver_info (kinematics_msgs/GetKinematicSolverInfo)
  • Used to get info on the IK solver.

Outputs

Action Outputs

follow_joint_trajectory/goal (control_msgs/FollowJointTrajectoryGoal)

  • Output to arm controller.

Published Topics

gripper_controller/command (std_msgs/Float64)
  • Output command to gripper.

Configuring for Your Robot

The simple_arm_server package has a launch file (launch/arm_server.launch) which can bring up the arm_kinematics package and the simple_arm_server with the correct parameters. To use this launch file, and supply it the correct parameters, you would add something like:

<launch>
  <include file="$(find simple_arm_server)/launch/arm_server.launch">
    <arg name="arm_dof" value="4" />
    <arg name="root_name" value="arm_base_link" />
     <arg name="tip_name" value="gripper_link" />
  </include>
</launch>

To your robot bringup launch file, supplying the correct root, tip and dof values for your robot.

Command Line Usage

The simple_arm_server_test.py script allows you to move the arm, using the server, through the command line:

$ simple_arm_server_test.py
usage: simple_arm_server_test.py x y z wrist_pitch [wrist_roll=0.0 wrist_yaw=0.0 frame_id='base_link' duration=5.0]

Small 5-DOF arms often have small workspaces. To get a starting point, you can see where the arm is in relation to the base using:

rosrun tf tf_echo base_link gripper_link

Wiki: simple_arm_server (last edited 2011-09-11 01:15:44 by MichaelFerguson)