Only released in EOL distros:  

nao_robot: nao_bringup | nao_description | nao_driver | nao_msgs | nao_pose

Package Summary

This package contains nodes for managing Nao's poses.

nao_robot: nao_apps | nao_bringup | nao_description

Package Summary

This package contains nodes for managing Nao's poses.

nao_robot: nao_apps | nao_bringup | nao_description

Package Summary

This package contains nodes for managing Nao's poses.

Package Summary

This package contains nodes for managing Nao's poses.

  • Maintainer: Séverin Lemaignan <severin.lemaignan AT epfl DOT ch>
  • Author: Armin Hornung, Séverin Lemaignan
  • License: BSD

Nodes

pose_manager

The pose manager maintains a library of poses so that clients can move the robot to a given pose by sending the name of the pose as an action goal.

Action Goal

body_pose (naoqi_msgs/BodyPose)
  • Goal containing the name of the pose as a string.

Actions Called

joint_trajectory (naoqi_msgs/JointTrajectory)
  • Sends the trajectory corresponding to the desired pose to the pose controller

Parameters

~xap (string)
  • File path for the file containing the pose library.
~poses (list)
  • Array containing additional poses.

pose_controller

Provides action servers for controlling the robot's joints by sending joint angles, joint trajectories, or stiffness values.

Action Goal

joint_angles_action/goal (naoqi_msgs/JointAnglesWithSpeedGoal)
  • Send joint angles goal
joint_trajectory/goal (naoqi_msgs/JointTrajectoryGoal)
  • Send joint trajectory goal
joint_stiffness_trajectory/goal (naoqi_msgs/JointTrajectoryGoal)
  • Send stiffness trajectory goal
body_pose_naoqi/goal (naoqi_msgs/BodyPoseWithSpeedGoal)
  • Send body pose goal. This action server is only available if a ALRobotPosture proxy is available.

Subscribed Topics

joint_angles (naoqi_msgs/JointAnglesWithSpeed)
  • Interpolate the joint angles to the given pose
joint_stiffness (sensor_msgs/JointState)
  • Set the stiffness for individual joints

Services

body_stiffness/disable (std_srvs/Empty)
  • Turn off all motors. Be careful as the robot might fall.
body_stiffness/enable (std_srvs/Empty)
  • Turn on all motors.
rest (std_srvs/Empty)
  • Put the robot in a safe pose and turn off the motors.
wakeup (std_srvs/Empty)
  • Turn on the motors and go to an initial position.

Parameters

~poll_rate (float, default: 0.2)
  • Get poll rate for actionlib (ie. how often to check whether currently running task has been preempted)
~init_stiffness (, default: 0.0)
  • initial stiffness (defaults to 0 so it doesn't strain the robot when no teleoperation is running), set to 1.0 if you want to control the robot immediately

Wiki: naoqi_pose (last edited 2015-08-03 15:19:48 by KarstenKnese)