Skip to content

Latest commit

 

History

History
173 lines (102 loc) · 3.28 KB

command-msgs.rst

File metadata and controls

173 lines (102 loc) · 3.28 KB

Command Msgs

The package nao_lola_command_msgs defines msgs used to send commands to the underlying NAO hardware.

Joints

JointPositions

By being able to specify the indexes, we can have different nodes sending partial joint position commands.

# Message to specify positions for the NAO's motor joints.
#
# Each joint is uniquely identified by its index (See JointIndexes.msg)
#
# The two arrays in this message should have the same size, where the first item
# in indexes, corresponds to the first item in positions, etc.

uint8[] indexes  # See JointIndexes.msg (eg. JointIndexes::HEADYAW)
float32[] positions # radians

JointStiffnesses

By being able to specify the indexes, we can have different nodes sending partial joint stiffness commands.

# Message to specify stiffnesses for the NAO's motor joints.
#
# Each joint is uniquely identified by its index (See JointIndexes.msg)
#
# The two arrays in this message should have the same size, where the first item
# in indexes, corresponds to the first item in stiffnesses, etc.

uint8[] indexes  # See JointIndexes.msg (eg. JointIndexes::HEADYAW)
float32[] stiffnesses  # 0.0 - 1.0

RGB Leds

Msgs that use std_msgs/ColorRGBA to specify colors for the RGB LEDs.

Note

Expect ranges for R, G and B are 0.0 - 1.0. The alpha value (A) is ignored.

ChestLed

A single RGB led in the chest.

std_msgs/ColorRGBA color  # r, g, b should be 0.0 - 1.0. a is ignored

LeftEyeLeds

See :ref:`left_eye_leds` to see which indexes correspond to which led.

std_msgs/ColorRGBA[8] colors

LeftFootLed

A single RGB led in the left foot.

std_msgs/ColorRGBA color

RightEyeLeds

See :ref:`right_eye_leds` to see which indexes correspond to which led.

std_msgs/ColorRGBA[8] colors

RightFootLed

A single RGB led in the right foot.

std_msgs/ColorRGBA color

Blue Leds

Msgs that specify intensity of the blue leds.

HeadLeds

See :ref:`head_leds` to see which indexes correspond to which led.

float32[12] intensities  # 0.0 - 1.0

LeftEarLeds

See :ref:`left_ear_leds` to see which indexes correspond to which led.

float32[10] intensities  # 0.0 - 1.0

RightEarLeds

See :ref:`right_ear_leds` to see which indexes correspond to which led.

float32[10] intensities  # 0.0 - 1.0

SonarUsage

Command to tell Lola whether to enable/disable the sonar.

bool left  # Set to true, to use left sonar
bool right  # Set to true, to use right sonar