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.
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 (lois added by default).plugin: plugin list withrateand optionalinstances/active_instances_at_startvalues.modulesandraisim_config: module list and simulation config file for Raisim.max_logging_volume(MB): forwarded toDataLogger::setAllowedDataSize.~/.raisin/raisin_raibo2/modulesfiles 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 |
|
Motor communication not started. |
1 |
|
Motor communication established. The motor drivers have not been initialized yet. |
2 |
|
Motor drivers initialized. Motors are ready to apply physical torque. |
3 |
|
(For manufacturer maintenance) Motor commutation in progress. |
4 |
|
Motor enabled. Motors are applying physical torque. The robot is ready to stand up or joint test. |
5 |
|
Running joint test. The |
6 |
|
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 |
7 |
|
A locomotion controller is loaded and running. This is the normal operating state. |
8 |
|
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
|
9 |
|
Motors disabled due to error. Entered when a critical fault is detected (e.g. Motor communication failure or motor driver exception). |
10 |
|
Motors in damping mode. The motors apply passive damping without active control. |
Interfaces
Publishers
robot_state
Type:
raisin::raisin_interfaces::msg::RobotStateHeader:
raisin_interfaces/msg/robot_state.hppMembers:
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 fromraibo::Stateenum. See Robot State for the full list of values.joy_listen_type(int32): Active joystick source type, cast fromSourceTypeenum.0–JOY: Listening to joystick input.1–VEL_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_statewhose type matchesjoy_listen_typeand whoseselectedfield isTrue. For more information, see Joy Interface.
module_list
Type:
raisin::raisin_interfaces::msg::ModuleListHeader:
raisin_interfaces/msg/module_list.hppMembers:
controllers[],loaded_controller,plugin_states[]Notes:
plugin_statesincludesname,instances[],is_loadable,is_unloadable.
profile
Type:
raisin::raisin_interfaces::msg::TimeProfileHeader:
raisin_interfaces/msg/time_profile.hppMembers:
cpu_usage,memory_usage,disk_usage,cpu_temperature,scope_measurements[](id,total_time,count)
threadpool
Type:
raisin::raisin_interfaces::msg::ThreadPoolProfileHeader:
raisin_interfaces/msg/thread_pool_profile.hppMembers:
thread_pool_profiles[](each includesevent_task_profiles[]andperiodic_task_profiles[]withname,execute_count,delay_sum,execution_time)
joint_states
Type:
raisin::raisin_interfaces::msg::JointStatesHeader:
raisin_interfaces/msg/joint_states.hppMembers:
timestamp,num_joints,joint_states[](joint_position,joint_velocity)
init_motor
Type:
raisin::std_msgs::msg::StringHeader:
std_msgs/msg/string.hppMembers:
dataNotes: Status updates for motor initialization.
stop_motor
Type:
raisin::std_msgs::msg::StringHeader:
std_msgs/msg/string.hppMembers:
dataNotes: Status updates for motor shutdown.
d430_front/grid_map_depth_data
Type:
raisin::raisin_grid_mapping_plugin::msg::GridMapDepthDataHeader:
raisin_grid_mapping_plugin/msg/grid_map_depth_data.hppNotes: 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::GridMapDepthDataHeader:
raisin_grid_mapping_plugin/msg/grid_map_depth_data.hppNotes: Republishes depth frames for grid mapping.
d455_front/grid_map_depth_data
Type:
raisin::raisin_grid_mapping_plugin::msg::GridMapDepthDataHeader:
raisin_grid_mapping_plugin/msg/grid_map_depth_data.hppNotes: Republishes depth frames for grid mapping.
Subscribers
command
Type:
raisin::raisin_interfaces::msg::CommandHeader:
raisin_interfaces/msg/command.hppMembers:
x_pos,y_pos,x_vel,y_vel,yaw_rate,pitch_angle,body_height,pan_dir,tilt_dirNotes: High-level body and velocity command input.
joy_sig
Type:
raisin::std_msgs::msg::Int16Header:
std_msgs/msg/int16.hppMembers:
dataNotes: Joystick signal for state changes (stand/sit/stop).
d430_front/depth
Type:
raisin::sensor_msgs::msg::ImageHeader:
sensor_msgs/msg/image.hppMembers:
header,height,width,encoding,is_bigendian,step,dataNotes: Forwarded to grid mapping when enabled.
d430_rear/depth
Type:
raisin::sensor_msgs::msg::ImageHeader:
sensor_msgs/msg/image.hppMembers:
header,height,width,encoding,is_bigendian,step,dataNotes: Forwarded to grid mapping when enabled.
d455_front/depth
Type:
raisin::sensor_msgs::msg::ImageHeader:
sensor_msgs/msg/image.hppMembers:
header,height,width,encoding,is_bigendian,step,dataNotes: Forwarded to grid mapping when enabled.
/Odometry/state_estimator
Type:
raisin::nav_msgs::msg::OdometryHeader:
nav_msgs/msg/odometry.hppMembers:
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::ImuHeader:
sensor_msgs/msg/imu.hppMembers:
header,orientation,orientation_covariance,angular_velocity,angular_velocity_covariance,linear_acceleration,linear_acceleration_covarianceNotes: Used for state estimation and logging.
Services
turn_on
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,messageNotes: Starts the robot loop if not already running.
turn_off
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,messageNotes: Stops the robot loop if running.
list_log_tree
Type:
raisin::raisin_interfaces::srv::LogTreeHeader:
raisin_interfaces/srv/log_tree.hppResponse 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::RobotDescriptionHeader:
raisin_interfaces/srv/robot_description.hppResponse 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::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,messageNotes: Initializes the motor control.
stop_motor
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,message
set_home_with_type
Type:
raisin::raisin_interfaces::srv::StringHeader:
raisin_interfaces/srv/string.hppRequest members used:
dataResponse members used:
success,messageNotes: Sets home offsets using the provided mode string.
joint_test
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,message
stand_up
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,message
sit_down
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,message
load_controller
Type:
raisin::raisin_interfaces::srv::StringHeader:
raisin_interfaces/srv/string.hppRequest members used:
dataResponse members used:
success,messageNotes: Loads a controller by name and unloads the current controller if needed.
motor_commutation
Type:
raisin::raisin_interfaces::srv::StringHeader:
raisin_interfaces/srv/string.hppRequest members used:
dataResponse members used:
success,message
load_plugin
Type:
raisin::raisin_interfaces::srv::LoadPluginHeader:
raisin_interfaces/srv/load_plugin.hppRequest members used:
plugin_name,title,flagResponse members used:
success,message
set_home
Type:
raisin::std_srvs::srv::TriggerHeader:
std_srvs/srv/trigger.hppRequest members used: none
Response members used:
success,messageNotes: Deprecated in favor of
set_home_with_type.
Clients
load_controller
Type:
raisin::raisin_interfaces::srv::StringHeader:
raisin_interfaces/srv/string.hppNotes: Internal polling client used to load the default locomotion controller after standing.