Low Level Service Interface
Function | C++ | ROS |
---|---|---|
Get Power Information | ✔ | ✔ |
Obtain Charging Information | ✔ | ✔ |
Enter/Exit Charging Mode | ✔ | |
Get IMU Data | ✔ | ✔ |
Charging Related Interface
Get Power Information
Obtain the power information of the robot
C++ Interface
rcClientInterfaceGetCommonStatus
Introduction
/**
* @brief Get general status information about the controlled robot (the main interface for robot status feedback).
*
* This function is used to get the general status information of the robot.
*
* @param com_state Pointer to a structure that holds information about the state of the robot.
* @return bool Returns `true` for success, `false` for failure.
*/
bool rcClientInterfaceGetCommonStatus(common::ROBOT_COMMON_STATUS *com_state);
Use Case
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;
} else {
std::cout << "Failed to Retrieve Common Status." << std::endl;
}
Precautions
- Com_state must point to a valid
common::ROBOT_COMMON_STATUS
structure.
ROS2 Interface
This interface is used to publish the battery level information of the robot.
Topic Name | Topic Type | Role |
---|---|---|
/battery_state | sensor_msgs::msg::BatteryState | Issued |
Message Structure
sensor_msgs::msg::BatteryState
the message type contains the following fields:
header
: Standard message headerpercentage
: Indicates the current percentage of battery power
Sample Message
sensor_msgs::msg::BatteryState battery_state_msg;
battery_state_msg.header.stamp = rclcpp::Time();
battery_state_msg.percentage = 75.0;
Test Method
Use the following command to view /battery_state
message from topic:
ros2 topic echo /battery_state
Obtain Charging Information
C++ Interface
rcClientInterfaceGetChargeStat
Introduction
/**
* @brief Read Jetson charging status.
*
* This function is used to read the current charging status of Jetson.
*
* @param charge_state pointer, used to store the read charge state.
* @return bool Returns `true` for a successful read, `false` for a failed read.
*/
bool rcClientInterfaceGetChargeState(common::JETSON_CHARGE_STATE *charge_state);
Use Case
common::JETSON_CHARGE_STATE charge_state;
bool success = rcClientInterfaceGetChargeState(&charge_state);
if (success) {
std::cout << "Jetson Charge State Read Successfully." << std::endl;
} else {
std::cout << "Failed to Read Jetson Charge State." << std::endl;
}
Precautions
- Ensure that the pointer passed in is valid and that the memory area pointed to can store the charging state.
ROS2 Interface
This interface is used to publish whether the robot is charging and to report to the inspection platform.
Topic Name | Topic Type | Role |
---|---|---|
/charge_state | std_msgs::msg::Bool | Issued |
Message Structure
std_msgs::msg::Bool
the message type contains the following fields:
data
: Indicates the current mode of the robot. The pattern code is as follows:true
: Chargingfalse
: Not charging
Sample Message
std_msgs::msg::Int32 msg;
msg.data = true;
Test Method
ros2 topic echo /dock_mode
Enter or Exit Charging Mode
C++ Interface
rcClientInterfaceEnterOrExitCharge
Introduction
/**
* @brief Entering or exiting the charging mode interface.
*
* This function is used to control the robot to enter or exit the charging mode.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param driver_enable Specifies whether to enable the charging mode (true means enter, false means exit).
* @return bool Returns `true` for successful setup, `false` for failed setup.
*/
bool rcClientInterfaceEnterOrExitCharge(
robot_control::common::NAV_OR_JOY_MODE from,
bool driver_enable);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
bool enable_charge = true; // Example value for entering 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;
}
Precautions
- Ensure that the incoming operating mode and charging mode enable states are valid.
Robot Sensor Data
Get IMU Data
C++ Interface (One Data at a Time)
rcClientInterfaceGetImuData
Introduction
/**
* @brief Get the current IMU data of the controlled robot (read one piece of data at a time).
* @brief
* This function is used to get the IMU (Inertial Measurement Unit) data of the current controlled robot.
*
* @param imu_data Pointer to the structure holding the IMU data.
* @return bool Returns `true` for successful retrieval, `false` for failed retrieval.
*/
bool rcClientInterfaceGetImuData(common::MC_MOTION_IMU_DATA *imu_data);
Use Case
common::MC_MOTION_IMU_DATA imu_data;
bool success = rcClientInterfaceGetImuData(&imu_data);
if (success) {
std::cout << "IMU Data Retrieved Successfully." << std::endl;
} else {
std::cout << "Failed to Retrieve IMU Data." << std::endl;
}
C++ Interface (Multiple Pieces of Data at a Time)
rcClientInterfaceGetImuStreamData
Introduction
/**
* @brief Get the current IMU data of the controlled robot (multiple reads at once).
*
* This function is used to get the current IMU (Inertial Measurement Unit) data stream of the controlled robot.
*
* @param imu_data_list Pointer to a vector holding IMU data.
* @return bool Returns `true` for successful retrieval, `false` for failure.
*/
bool rcClientInterfaceGetImuStreamData(std::vector<common::MC_MOTION_IMU_DATA> *imu_data_list);
Use Case
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;
} else {
std::cout << "Failed to Retrieve IMU Stream Data." << std::endl;
}
Precautions
- The IMU_data_list must point to a valid
std::vector<common::MC_MOTION_IMU_DATA>
- Ensure that the client-server connection has been successfully initialized before calling the function.
ROS2 Interface
This interface is used to publish IMU sensor data. IMU usually contains accelerometer, gyroscope and magnetometer measurement data. IMU topic subscribes to the robot's attitude, angular velocity, and linear acceleration.
Topic Name | Topic Type | Role |
---|---|---|
/imu | /sensor_msgs::msg::Imu | Issued |
Message Structure
/sensor_msgs::msg::Imu
the message type contains the following fields:
header
: Standard message headerorientation
contains attitude informationangular_velocity
contains angular velocity informationlinear_acceleration
contains linear acceleration information
Sample 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;
Test Method
ros2 topic echo /rc_imu