Skip to content

Latest commit

 

History

History
64 lines (47 loc) · 3.29 KB

lola-client.rst

File metadata and controls

64 lines (47 loc) · 3.29 KB

LoLA Client

To run the client that connects to LoLA, run:

ros2 run nao_lola_client nao_lola_client

Published Topics

  • sensors/accelerometer (nao_lola_sensor_msgs::msg::Accelerometer <Accelerometer>)
  • sensors/angle (nao_lola_sensor_msgs::msg::Angle <Angle>)
  • sensors/buttons (nao_lola_sensor_msgs::msg::Buttons <Buttons>)
  • sensors/fsr (nao_lola_sensor_msgs::msg::FSR <FSR>)
  • sensors/gyroscope (nao_lola_sensor_msgs::msg::Gyroscope <Gyroscope>)
  • sensors/joint_positions (nao_lola_sensor_msgs::msg::JointPositions <sensor_joint_positions>)
  • sensors/joint_stiffnesses (nao_lola_sensor_msgs::msg::JointStiffnesses <sensor_joint_stiffnesses>)
  • sensors/joint_temperatures (nao_lola_sensor_msgs::msg::JointTemperatures <JointTemperatures>)
  • sensors/joint_currents (nao_lola_sensor_msgs::msg::JointCurrents <JointCurrents>)
  • sensors/joint_statuses (nao_lola_sensor_msgs::msg::JointStatuses <JointStatuses>)
  • sensors/sonar (nao_lola_sensor_msgs::msg::Sonar <Sonar>)
  • sensors/touch (nao_lola_sensor_msgs::msg::Touch <Touch>)
  • sensors/battery (nao_lola_sensor_msgs::msg::Battery <Battery>)
  • sensors/robot_config (nao_lola_sensor_msgs::msg::RobotConfig <RobotConfig>)

The following topics are available depending on parameters:

Subscribed Topics

  • effectors/joint_positions (nao_lola_command_msgs::msg::JointPositions <command_joint_positions>)
  • effectors/joint_stiffnesses (nao_lola_command_msgs::msg::JointStiffnesses <command_joint_stiffnesses>)
  • effectors/chest_led (nao_lola_command_msgs::msg::ChestLed <ChestLed>)
  • effectors/left_ear_leds (nao_lola_command_msgs::msg::LeftEarLeds <LeftEarLeds>)
  • effectors/right_ear_leds (nao_lola_command_msgs::msg::RightEarLeds <RightEarLeds>)
  • effectors/left_eye_leds (nao_lola_command_msgs::msg::LeftEyeLeds <sensor_LeftEyeLeds>)
  • effectors/right_eye_leds (nao_lola_command_msgs::msg::RightEyeLeds <sensor_RightEyeLeds>)
  • effectors/left_foot_led (nao_lola_command_msgs::msg::LeftFootLed <sensor_LeftFootLed>)
  • effectors/right_foot_led (nao_lola_command_msgs::msg::RightFootLed <sensor_RightFootLed>)
  • effectors/head_leds (nao_lola_command_msgs::msg::HeadLeds <sensor_HeadLeds>)
  • effectors/sonar_usage (nao_lola_command_msgs::msg::SonarUsage <SonarUsage>)

Parameters

  • publish_imu (bool, default: true)

    Whether to convert nao_lola sensor_msgs/Accelerometer and nao_lola sensor_msgs/Gyroscope to sensor_msgs/Imu and publish it.

  • publish_joint_states (bool, default: true)

    Whether to convert nao_lola sensor_msgs/JointPositions to sensor_msgs/JointState and publish it.