Interface ========== .. image:: https://github.com/qcr/armer/wiki/armer_architecture.png :alt: Armer architecture diagram This diagram shows the layers a user command goes through to finally be translated into movement on the robot. (Open the image in a new tab to see with greater resolution) The following ROS components are utilized by Armer to allow the user to command with an arm. For more details on how to use these interfaces see the tutorials. Subscribed Topics ------------------- * **/arm/cartesian/velocity** `geometry_msgs/TwistStamped `_ Moves the end-effector in Cartesian space w.r.t. the target frame_id (base frame if no frame_id is set). * **/arm/joint/velocity** `armer_msgs/JointVelocity `_ Moves the joints of the manipulator at the requested velocity. Published Topics ----------------- * **/arm/state** `armer_msgs/ManipulatorState `_ Provides information on the current state of the manipulator including the pose of the end-effector w.r.t. to the base link, whether the manipulator is experiencing a cartesian contact and collision as a bit-wised error state flag. Services ----------- * **/arm/home** `std_srvs/Empty `_ Moves the robot back to its initial ready pose. * **/arm/recover** `std_srvs/Empty `_ Recovers from collision or limit violation error states that will put the robot into a non-operable state. * **/arm/stop** `std_srvs/Empty `_ Stops the current motion of the current. * **/arm/get_named_poses** `armer_msgs/GetNamedPoses `_ Gets a list of currently stored named poses (includes both moveit and Armer stored named poses). * **/arm/set_named_pose** `armer_msgs/AddNamedPose `_ Saves the current joint configuration of the robot with the provided pose name. * **/arm/remove_named_pose** `armer_msgs/RemoveNamedPose `_ Removes the joint configuration of the provided pose name. * **/arm/set_cartesian_impedance** `armer_msgs/SetCartesianImpedance `_ Adjusts the impedance of the end-effector position in Cartesian space. * **/arm/add_named_pose_config** `armer_msgs/AddNamedPoseConfig `_ Instructs Armer to load named poses stored in the indicated config file. * **/arm/get_named_pose_configs** `armer_msgs/GetNamedPoseConfigs `_ Gets the list of config files to check for named poses. * **/arm/remove_named_pose_config** `armer_msgs/RemoveNamedPoseConfig `_ Instructs Armer to remove named poses stored in the indicated config file. Action Servers ---------------- * **/arm/cartesian/pose** `armer_msgs/MoveToPose.action `_ Moves the end-effector to the requested goal pose w.r.t. the indicated frame id. * **/arm/cartesian/servo_pose** `armer_msgs/ServoToPose.action `_ Servos the end-effector to the requested goal pose with real time object avoidance. * **/arm/joint/named** `armer_msgs/MoveToNamedPose.action `_ Moves the end-effector to a pre-defined joint configuration. * **/arm/joint/pose** `armer_msgs/MoveToJointPoseAction.action `_ Moves the joints of the robot to the indicated positions (radians).