RaiboNode

The source code for Raibo Node can be found in src/raisin_raibo2.

This node primarily facilitates communication between worldHub_ and other components. It initializes a raisin::Network instance, launches both TCP and WebSocket servers, and manages logging and plugin/controller lifecycles.

raisin_diagram

Run

These commands can also be executed using the raisin_gui

Run In simulation

If you installed the binary package, simply run the executable after raisin setup

The executable is install/bin/raisin_raibo2_node.

Change Configuration

Configuration is loaded from $raisin_ws/install/config/raisin_raibo2/config/params.yaml and overrides in ~/.raisin/raisin_raibo2/params.yaml. Key settings include:

  • threads: defines thread groups (thread_0, thread_1, …) that must be consecutive.

  • network_interface: list of network interface names for discovery (lo is added by default).

  • plugin: plugin list with rate and optional instances / active_instances_at_start values.

  • modules and raisim_config: module list and simulation config file for Raisim.

  • max_logging_volume (MB): forwarded to DataLogger::setAllowedDataSize.

  • ~/.raisin/raisin_raibo2/modules files are copied into the installed resource directory at startup to make custom modules available.

Logs are stored under log/raisin_data_logger/<deviceType>_YYYY-mm-dd-hh-mm-ss/ in the workspace.

Ensure that the camera is properly configured, including settings for use_depth and use_rgb, and serial_number. This configuration is essential for the camera to function correctly according to your requirements. If a sensor is not connected on a real robot, make sure to set use_sensor false, otherwise the robot will not operate.

It subscribes to the joy_sig topic to receive joystick state changes and to command for high-level velocity/body commands. Controllers and plugins can be loaded through services listed below.

Robot State

The raibo::State enum (defined in raisin_raibo2/raibo_state.hpp) represents the lifecycle of the robot node. The value is published as the state field in the robot_state topic.

Caution

From MOTOR_ENABLED (4) onward, the motors generate physical torque. Ensure the robot is in a safe environment and all personnel are clear of the robot before transitioning to this state.

Value

Name

Description

0

COMM_DISABLED

Motor communication not started.

1

COMM_ENABLED

Motor communication established. The motor drivers have not been initialized yet.

2

MOTOR_READY

Motor drivers initialized. Motors are ready to apply physical torque.

3

MOTOR_COMMUTATION

(For manufacturer maintenance) Motor commutation in progress.

4

MOTOR_ENABLED

Motor enabled. Motors are applying physical torque. The robot is ready to stand up or joint test.

5

IN_TEST_MODE

Running joint test. The joint_test service has been called and the test controller is exercising each joint. The joint test must be run at least once after the robot is powered on.

6

STANDING_MODE

Stand-up (recovery) controller active. The robot is transitioning from a sitting posture to a standing posture. Once the stand-up finishes, the default locomotion controller is loaded automatically and the state transitions to IN_CONTROL.

7

IN_CONTROL

A locomotion controller is loaded and running. This is the normal operating state.

8

SITDOWN_MODE

Sit-down controller active. The robot is transitioning from a standing posture to a sitting posture. Once the sit-down controller finishes, the state transitions back to MOTOR_ENABLED.

9

MOTOR_DISABLED

Motors disabled due to error. Entered when a critical fault is detected (e.g. Motor communication failure or motor driver exception).

10

MOTOR_DAMPING

Motors in damping mode. The motors apply passive damping without active control.

Interfaces

Publishers

robot_state

  • Type: raisin::raisin_interfaces::msg::RobotState

  • Header: raisin_interfaces/msg/robot_state.hpp

  • Members:

    • timestamp (builtin_interfaces/Time): Current time. On a real robot this is the system clock; in simulation it is the world simulation time.

    • actuator_states[] (ActuatorState[]): Array of actuator states. Each entry contains:

      • name (string): Joint name.

      • position (float64): Joint position.

      • velocity (float64): Joint velocity.

      • effort (float64): Joint torque.

      • status (uint16): Motor status word from the motor driver.

      • temperature (float64): Motor temperature.

    • base_pos[3] (float64[3]): Base position [x, y, z].

    • base_quat[4] (float64[4]): Base orientation quaternion [w, x, y, z].

    • base_lin_vel[3] (float64[3]): Base linear velocity [x, y, z].

    • base_ang_vel[3] (float64[3]): Base angular velocity [x, y, z].

    • imu (Imu): IMU sensor reading.

      • quaternion_w, quaternion_x, quaternion_y, quaternion_z (float64): Orientation quaternion from the IMU.

      • angular_velocity_x, angular_velocity_y, angular_velocity_z (float64): Angular velocity measured by the IMU gyroscope.

      • linear_acceleration_x, linear_acceleration_y, linear_acceleration_z (float64): Linear acceleration measured by the IMU accelerometer.

    • max_voltage (float64): Maximum allowed battery voltage.

    • min_voltage (float64): Minimum allowed battery voltage.

    • max_current (float64): Maximum allowed current.

    • voltage (float64): Current battery voltage.

    • current (float64): Current battery current.

    • body_temperature (float64): Body temperature.

    • state (int32): Current robot state, cast from raibo::State enum. See Robot State for the full list of values.

    • joy_listen_type (int32): Active joystick source type, cast from SourceType enum.

      • 0JOY: Listening to joystick input.

      • 1VEL_CMD: Listening to velocity command input.

    • joy_listen_state[] (JoyListen[]): Status of each joystick source. Each entry contains:

      • topic (string): topic name of the source.

      • network_id (string): Network identifier of the source publisher.

      • selected (bool): Whether this source is currently selected.

      • online (bool): Whether this source is currently connected.

    Note

    The currently active command source is the entry in joy_listen_state whose type matches joy_listen_type and whose selected field is True. For more information, see Joy Interface.

module_list

  • Type: raisin::raisin_interfaces::msg::ModuleList

  • Header: raisin_interfaces/msg/module_list.hpp

  • Members: controllers[], loaded_controller, plugin_states[]

  • Notes: plugin_states includes name, instances[], is_loadable, is_unloadable.

profile

  • Type: raisin::raisin_interfaces::msg::TimeProfile

  • Header: raisin_interfaces/msg/time_profile.hpp

  • Members: cpu_usage, memory_usage, disk_usage, cpu_temperature, scope_measurements[] (id, total_time, count)

threadpool

  • Type: raisin::raisin_interfaces::msg::ThreadPoolProfile

  • Header: raisin_interfaces/msg/thread_pool_profile.hpp

  • Members: thread_pool_profiles[] (each includes event_task_profiles[] and periodic_task_profiles[] with name, execute_count, delay_sum, execution_time)

joint_states

  • Type: raisin::raisin_interfaces::msg::JointStates

  • Header: raisin_interfaces/msg/joint_states.hpp

  • Members: timestamp, num_joints, joint_states[] (joint_position, joint_velocity)

init_motor

  • Type: raisin::std_msgs::msg::String

  • Header: std_msgs/msg/string.hpp

  • Members: data

  • Notes: Status updates for motor initialization.

stop_motor

  • Type: raisin::std_msgs::msg::String

  • Header: std_msgs/msg/string.hpp

  • Members: data

  • Notes: Status updates for motor shutdown.

d430_front/grid_map_depth_data

  • Type: raisin::raisin_grid_mapping_plugin::msg::GridMapDepthData

  • Header: raisin_grid_mapping_plugin/msg/grid_map_depth_data.hpp

  • Notes: Republishes depth frames for grid mapping. Published only when the grid mapping plugin is available.

d430_rear/grid_map_depth_data

  • Type: raisin::raisin_grid_mapping_plugin::msg::GridMapDepthData

  • Header: raisin_grid_mapping_plugin/msg/grid_map_depth_data.hpp

  • Notes: Republishes depth frames for grid mapping.

d455_front/grid_map_depth_data

  • Type: raisin::raisin_grid_mapping_plugin::msg::GridMapDepthData

  • Header: raisin_grid_mapping_plugin/msg/grid_map_depth_data.hpp

  • Notes: Republishes depth frames for grid mapping.

Subscribers

command

  • Type: raisin::raisin_interfaces::msg::Command

  • Header: raisin_interfaces/msg/command.hpp

  • Members: x_pos, y_pos, x_vel, y_vel, yaw_rate, pitch_angle, body_height, pan_dir, tilt_dir

  • Notes: High-level body and velocity command input.

joy_sig

  • Type: raisin::std_msgs::msg::Int16

  • Header: std_msgs/msg/int16.hpp

  • Members: data

  • Notes: Joystick signal for state changes (stand/sit/stop).

d430_front/depth

  • Type: raisin::sensor_msgs::msg::Image

  • Header: sensor_msgs/msg/image.hpp

  • Members: header, height, width, encoding, is_bigendian, step, data

  • Notes: Forwarded to grid mapping when enabled.

d430_rear/depth

  • Type: raisin::sensor_msgs::msg::Image

  • Header: sensor_msgs/msg/image.hpp

  • Members: header, height, width, encoding, is_bigendian, step, data

  • Notes: Forwarded to grid mapping when enabled.

d455_front/depth

  • Type: raisin::sensor_msgs::msg::Image

  • Header: sensor_msgs/msg/image.hpp

  • Members: header, height, width, encoding, is_bigendian, step, data

  • Notes: Forwarded to grid mapping when enabled.

/Odometry/state_estimator

  • Type: raisin::nav_msgs::msg::Odometry

  • Header: nav_msgs/msg/odometry.hpp

  • Members: header, child_frame_id, pose (position + orientation + covariance), twist (linear + angular velocity + covariance)

  • Notes: Used for base state estimation and sensor pose updates.

base_imu/imu

  • Type: raisin::sensor_msgs::msg::Imu

  • Header: sensor_msgs/msg/imu.hpp

  • Members: header, orientation, orientation_covariance, angular_velocity, angular_velocity_covariance, linear_acceleration, linear_acceleration_covariance

  • Notes: Used for state estimation and logging.

Services

turn_on

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

  • Notes: Starts the robot loop if not already running.

turn_off

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

  • Notes: Stops the robot loop if running.

list_log_tree

  • Type: raisin::raisin_interfaces::srv::LogTree

  • Header: raisin_interfaces/srv/log_tree.hpp

  • Response members used: username, prefix, ssh_port, dirs[], sizes[]

  • Notes: Lists log directories and sizes for the current robot.

describe_robot

  • Type: raisin::raisin_interfaces::srv::RobotDescription

  • Header: raisin_interfaces/srv/robot_description.hpp

  • Response members used: success, is_real_robot, robot_model, robot_nickname, serial_number, driver_version, robot_software_version, max_voltage, min_voltage, max_current

init_motor

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

  • Notes: Initializes the motor control.

stop_motor

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

set_home_with_type

  • Type: raisin::raisin_interfaces::srv::String

  • Header: raisin_interfaces/srv/string.hpp

  • Request members used: data

  • Response members used: success, message

  • Notes: Sets home offsets using the provided mode string.

joint_test

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

stand_up

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

sit_down

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

load_controller

  • Type: raisin::raisin_interfaces::srv::String

  • Header: raisin_interfaces/srv/string.hpp

  • Request members used: data

  • Response members used: success, message

  • Notes: Loads a controller by name and unloads the current controller if needed.

motor_commutation

  • Type: raisin::raisin_interfaces::srv::String

  • Header: raisin_interfaces/srv/string.hpp

  • Request members used: data

  • Response members used: success, message

load_plugin

  • Type: raisin::raisin_interfaces::srv::LoadPlugin

  • Header: raisin_interfaces/srv/load_plugin.hpp

  • Request members used: plugin_name, title, flag

  • Response members used: success, message

set_home

  • Type: raisin::std_srvs::srv::Trigger

  • Header: std_srvs/srv/trigger.hpp

  • Request members used: none

  • Response members used: success, message

  • Notes: Deprecated in favor of set_home_with_type.

Clients

load_controller

  • Type: raisin::raisin_interfaces::srv::String

  • Header: raisin_interfaces/srv/string.hpp

  • Notes: Internal polling client used to load the default locomotion controller after standing.

Development