Basic Service Interfaces
Function | C++ | ROS |
---|---|---|
Get battery status | ✔ | ✔ |
Get charging status | ✔ | ✔ |
Enter/Exit charging mode | ✔ | |
Get IMU data | ✔ | ✔ |
Charging Related Interfaces
Get Battery Status
C++ Interface
Function:rcClientInterfaceGetCommonStatus
/**
* @brief Get general status information of the controlled robot (main feedback interface).
*
* This function retrieves the general status of the robot.
*
* @param com_state Pointer to a structure that will hold the robot's status.
* @return bool Returns `true` if successful, otherwise `false`.
*/
bool rcClientInterfaceGetCommonStatus(common::ROBOT_COMMON_STATUS *com_state);
Example:
common::ROBOT_COMMON_STATUS com_state;
bool success = rcClientInterfaceGetCommonStatus(&com_state);
if (success) {
float charge_level= com_state.charge_status.battery_info.level;
auto charge_state = com_state.charge_status.battery_info.state;
std::cout << "Common Status Retrieved Successfully." << std::endl;
// Output or process the com_state data
} else {
std::cout << "Failed to Retrieve Common Status." << std::endl;
}
WARNING
Note:com_state
must be a valid pointer to a common::ROBOT_COMMON_STATUS
structure.
ROS2 Interface
This interface is used to publish the battery status information of the robot.
Topic Name | Topic Type | Role |
---|---|---|
/battery_state | sensor_msgs::msg::BatteryState | Publisher |
Message Structure
The message type sensor_msgs::msg::BatteryState
contains the following fields:
header
: Standard message headerpercentage
: Indicates the current battery level as a percentage
Example Message
sensor_msgs::msg::BatteryState battery_state_msg;
battery_state_msg.header.stamp = rclcpp::Time();
battery_state_msg.percentage = 75.0; // 75% battery level
Test Method
Use the following command to monitor messages from the /battery_state
topic:
ros2 topic echo /battery_state
Retrieve Charging Information
C++ Interface
Function Name:rcClientInterfaceGetChargeState
/**
* @brief Read the Jetson charging status.
*
* This function is used to retrieve the current charging status of the Jetson module.
*
* @param charge_state Pointer to store the retrieved charging status.
* @return bool Returns `true` if reading was successful, `false` otherwise.
*/
bool rcClientInterfaceGetChargeState(common::JETSON_CHARGE_STATE *charge_state);
Example Usage:
common::JETSON_CHARGE_STATE charge_state;
bool success = rcClientInterfaceGetChargeState(&charge_state);
if (success) {
std::cout << "Jetson Charge State Read Successfully." << std::endl;
// Handle the retrieved charge_state data
} else {
std::cout << "Failed to Read Jetson Charge State." << std::endl;
}
WARNING
Notes:
- Make sure the pointer you pass in is valid and points to a memory region large enough to hold the charging status data.
ROS2 Interface
This interface publishes the robot's charging status to the inspection platform.
Topic Name | Topic Type | Role |
---|---|---|
/charge_state | std_msgs::msg::Bool | Publisher |
Message Structure
The std_msgs::msg::Bool
message type contains the following field:
data
: Indicates the current mode of the robot. The mode codes are as follows:true
: Chargingfalse
: Not Charging
Example Message:
std_msgs::msg::Int32 msg;
msg.data = true;
Test Message:
ros2 topic echo /dock_mode
Enter or Exit Charging Mode
C++ Interface
Function:rcClientInterfaceEnterOrExitCharge
/**
* @brief Interface to enter or exit charging mode.
*
* This function is used to control the robot to enter or exit charging mode.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param driver_enable Specifies whether to enable charging mode (true = enter, false = exit).
* @return bool Returns `true` if the setting is successful, `false` otherwise.
*/
bool rcClientInterfaceEnterOrExitCharge(
robot_control::common::NAV_OR_JOY_MODE from,
bool driver_enable);
Usage Example
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
bool enable_charge = true; // Example value: enter charging mode
bool success = rcClientInterfaceEnterOrExitCharge(mode, enable_charge);
if (success) {
std::cout << "Charge Mode Set Successfully." << std::endl;
} else {
std::cout << "Failed to Set Charge Mode." << std::endl;
}
WARNING
Notes
- Ensure the input operation mode (
**from**
) and the charging mode flag (**driver_enable**
) are valid before calling the function.
Robot Sensor Data
Retrieve IMU Data
C++ Interface (Single Data Entry)
Function:rcClientInterfaceGetImuData
/**
* @brief Retrieve IMU data (one entry at a time) from the currently controlled robot.
*
* This function is used to obtain the Inertial Measurement Unit (IMU) data of the currently controlled robot.
*
* @param imu_data Pointer to the structure where the IMU data will be stored.
* @return bool Returns `true` if the data is successfully retrieved, `false` otherwise.
*/
bool rcClientInterfaceGetImuData(common::MC_MOTION_IMU_DATA *imu_data);
Usage Example:
common::MC_MOTION_IMU_DATA imu_data;
bool success = rcClientInterfaceGetImuData(&imu_data);
if (success) {
std::cout << "IMU Data Retrieved Successfully." << std::endl;
// Output or process the imu_data
} else {
std::cout << "Failed to Retrieve IMU Data." << std::endl;
}
C++ Interface (Multiple Data Entries)
Function:rcClientInterfaceGetImuStreamData
/**
* @brief Retrieve a stream of IMU data (multiple entries at once) from the currently controlled robot.
*
* This function is used to retrieve a batch of IMU (Inertial Measurement Unit) data from the robot.
*
* @param imu_data_list Pointer to the vector that will store the IMU data stream.
* @return bool Returns `true` if the data is successfully retrieved, `false` otherwise.
*/
bool rcClientInterfaceGetImuStreamData(std::vector<common::MC_MOTION_IMU_DATA> *imu_data_list);
Usage Example:
std::vector<common::MC_MOTION_IMU_DATA> imu_data_list;
bool success = rcClientInterfaceGetImuStreamData(&imu_data_list);
if (success) {
std::cout << "IMU Stream Data Retrieved Successfully." << std::endl;
// Output or process the imu_data_list
} else {
std::cout << "Failed to Retrieve IMU Stream Data." << std::endl;
}
WARNING
Notes:
**imu_data_list**
** must point to a valid**std::vector<common::MC_MOTION_IMU_DATA>**
.**- Make sure the client-server connection is properly initialized before calling this function.
ROS2 Interface
This interface is used to publish IMU sensor data. The IMU typically includes measurements from accelerometers, gyroscopes, and magnetometers. Robot posture, angular velocity, and linear acceleration are published via the /imu
topic.
Topic Name | Topic Type | Role |
---|---|---|
/imu | /sensor_msgs::msg::Imu | Publisher |
Message Structure (**sensor_msgs::msg::Imu**
):
header
: Standard message headerorientation
: Orientation (quaternion)angular_velocity
: Angular velocity (rad/s)linear_acceleration
: Linear acceleration (m/s²)
Example Message:
sensor_msgs::msg::Imu imu_msg;
imu_msg.header.stamp = rclcpp::Time();
imu_msg.header.frame_id = "imu";
imu_msg.orientation.x = 0.0;
imu_msg.orientation.y = 0.0;
imu_msg.orientation.z = 0.0;
imu_msg.orientation.w = 1.0;
imu_msg.angular_velocity.x = 0.0;
imu_msg.angular_velocity.y = 0.0;
imu_msg.angular_velocity.z = 0.0;
imu_msg.linear_acceleration.x = 0.0;
imu_msg.linear_acceleration.y = 0.0;
imu_msg.linear_acceleration.z = 0.0;
Testing Command:
ros2 topic echo /rc_imu