Only released in EOL distros:  

nao_robot: nao_apps | nao_bringup | nao_description

Package Summary

Applications for NAO using the NAOqi API

nao_robot: nao_apps | nao_bringup | nao_description

Package Summary

Applications for NAO using the NAOqi API

Package Summary

Applications for NAO using the NAOqi API

  • Maintainer status: maintained
  • Maintainer: Vincent Rabaud <vincent.rabaud AT gmail DOT com>
  • Author:
  • License: BSD
nao_robot: nao_apps | nao_bringup | nao_description

Package Summary

Applications for NAO using the NAOqi API

Nodes

nao_alife

ROS node to interface with Naoqi Autonomous Life modules. See the Nao documentation for a description of the individual states.

Services

nao_alife/disabled (std_srvs/Empty)
  • Set the robot's state to disabled.
nao_alife/interactive (std_srvs/Empty)
  • Set the robot's state to interactive.
nao_alife/safeguard (std_srvs/Empty)
  • Set the robot's state to safeguard.
nao_alife/solitary (std_srvs/Empty)
  • Set the robot's state to solitary.

nao_behaviors

nao_behaviors allows you to query and execute pre-recorded actions on the NAO. Note a node may only execute one behaviour at a time. You can use choregraphe to generate behaviors (Box libraries->Templates->Animation).

Action Goal

run_behavior (naoqi_msgs/RunBehaviorGoal)
  • Executes an already installed behavior

Services

get_installed_behaviors (naoqi_msgs/GetInstalledBehaviors)
  • Returns a list of the installed behaviors on the robot

nao_diagnostic_updater

This script collects diagnostic information on a Nao robot and publishes the information as DiagnosticArray messages (last tested with NaoQI 1.10.52). CPU temperature and network status will only be available if the script runs directly on the robot.

Published Topics

diagnostics (diagnostic_msgs/DiagnosticArray)
  • Dignostic messages

nao_footsteps

nao_footsteps handles footsteps meant to be executed on the NAO robot. It offers a topic and a service to execute footsteps on the NAO robot, as well as a service to clip footsteps which can be afterwards performed by the NAO robot.

Subscribed Topics

footstep (humanoid_nav_msgs/StepTarget)
  • Sends a footstep command to the NAO robot.

Services

footstep_srv (humanoid_nav_msgs/StepTargetService)
  • Sends a footstep command to the NAO robot. The service blocks until the footstep has been executed.
clip_footstep_srv (humanoid_nav_msgs/ClipFootstep)
  • Clips a footstep into the range executable by the NAO robot.

Parameters

~init_stiffness (float, 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

nao_leds

nao_leds can control all the LEDs on the NAO. It also allows to activate a customazible blinking behavior.

Action Goal

blink (naoqi_msgs/BlinkGoal)
  • NAO will blink with a color chosen at random from colors, the duration of the actual blink is determined by blink_duration and the blinking rate is assumed to be normal with mean blink_rate_mean and standard deviation blink_rate_sd. The background color while the robot is not blinking is set to bg_color. This behavior runs until either a new BlinkGoal is sent or the current goal is cancelled.

Subscribed Topics

fade_rgb (naoqi_msgs/FadeRGB)
  • Set the leds represented by led_name to color. Transisition lasts for fade_duration. For more information about valid names refer to the NAOqi documentation.

nao_speech

Node leverages both NaoQi's text-to-speech and speech recognition engines and exposes them to ROS. It is possible to have several concurrent nodes of this type, each one configured with different parameters.

Action Goal

speech_action/goal (naoqi_msgs/SpeechWithFeedback)
  • Text to be spoken by Nao's speech synthesis
/speech_vocabulary_action/goal (naoqi_msgs/SetSpeechVocabulary)
  • List of words to be recognized by NAO. Must not be empty for speech recognizer to work.

Subscribed Topics

speech (std_msgs/String)
  • Text to be said over Nao's speech synthesis.

Published Topics

word_recognized (naoqi_msgs/WordRecognized)
  • Words and confidence levels detected with Nao's speech recognition system.

Services

reconfigure (std_srvs/Empty)
  • Call to reconfigure node using ROS parameters, useful if parameters have been updated since node start-up.
start_recognition (std_srvs/Empty)
  • Start Nao's speech recognition system. The vocabulary parameters needs to be set for the call to succeed. Only one node can use the speech recognition at any given time.
stop_recognition (std_srvs/Empty)
  • Stop speech recognition. Useful to allow other nao_speech nodes to start the speech recognition system.

Parameters

~voice (string, default: current voice)
  • Set NAO's voice
~language (string, default: current language)
  • Set NAO's language (both text-to-speech and speech recognition)
~volume (float, default: current volume)
  • Set NAO's voice volume
~vocabulary (list of strings, default: empty list)
  • List of words to be recognized by NAO. Must not be empty for speech recognizer to work.
~enable_audio_expression (boolean, default: current value)
  • Enable speech recognizer's audio expression
~enable_visual_expression (boolean, default: current value)
  • Enable speech recognizer's visual expression
~word_spotting (boolean, default: false)
  • Enable word spotting (recognizing words in the middle of a speech) only if your NAO supports it (>v4)

nao_tactile

Publishes sensor data of Nao's tactile sensors and bumpers. A message is sent whenever the state of the touch sensors or bumpers change, and the full state (pressed / touched or not) is sent.

Published Topics

tactile_touch (naoqi_msgs/TactileTouch)
  • Contains information about which tactile button on Nao's head was touched
bumper (naoqi_msgs/Bumper)
  • Contains information about which bumper (left or right) was triggered.
foot_contact (std_msgs/Bool)
  • Indicates whether at least one of the feet touches the ground.

nao_walker

nao_walker provides teleoperation with an omnidirectional walk by wrapping the Aldebaran Python NaoQI API. Accessing Nao's speech synthesis is also possible with the topic speech.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • Omnidirectional velocity (x, y, and theta) for the walking engine
cmd_pose (geometry_msgs/Pose2D)
  • Send a goal in cartesian coordinates to the walking engine
cmd_step (humanoid_nav_msgs/StepTarget)
  • Send footsteps to the walking engine

Services

read_foot_gait_config_srv (std_srvs/Empty)
  • Reads the values from ~use_foot_gait_config and ~foot_gait_config and sets them. This can be used to change the current foot gait config during runtime.
cmd_vel_srv (naoqi_msgs/CmdVelService)
  • Send a velocity to the walking engine
cmd_step_srv (humanoid_nav_msgs/StepTargetService)
  • Send a footstep target to the walking engine
cmd_pose_srv (naoqi_msgs/CmdPoseService)
  • Send a pose in cartesian coordinates to the walking engine
stop_walk_srv (std_srvs/Empty)
  • Stop walking immediately
needs_start_walk_pose_srv (std_srvs/Empty)
  • Sets a flag indicating whether the robot should go to a posture suitable for walking first before starting to walk
enable_arms_walking_srv (naoqi_msgs/SetArmsEnabled)
  • Enable or disable swinging the arms while walking

Parameters

~step_frequency (double, default: 0.5)
  • Maximum fraction of Nao's step frequency to be used when walking (between 0 and 1). This controls how fast (and stable) Nao is walking.
~use_walk_pose (boolean, default: False)
  • Slowly move from init pose to walk pose before walking to avoid toppling over backwards (might improve stability for naoqi versions >= 1.10.10, not tested for other versions)
~enable_foot_contact_protection (boolean)
  • Enable or disable foot contact protection in robot's motion configuration. If this parameter is not specified, the current setting will not be changed.
~use_foot_gait_config (boolean, default: False)
  • Enable or disable using a foot gait configuration for all walk commands. Disabling will use the Default gait configuration saved on the Nao.
~foot_gait_config (ALValue/Tupel)
  • A list of the gait config parameters, see the NAOqi API for more information.
~init_stiffness (float)
  • 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: nao_apps (last edited 2015-03-19 17:02:49 by StefanOsswald)