High Level Motion Service Interface
Introduction
High level control interface: Send speed control, attitude control and other motion instructions to Daystar Robot by calling ROS2 Topic/ROS2 Service/C ++ function.
Function | C++ | ROS |
---|---|---|
Up and down enable | ✔ | |
Control movement direction and speed | ✔ | ✔ |
Adjusting standing height | ✔ | ✔ |
Set the current running scenario | ✔ | ✔ |
Demo Mode Control | ✔ | |
Adjust the operating speed | ✔ | |
Software Emergency Stop | ✔ | |
Recovery software emergency stop | ✔ | |
Set control mode | ✔ | ✔ |
Upward and Downward Enable
C++ Interface
rcClientInterfaceDriverEnable
Introduction
/**
* @brief Control the upper and lower enable interfaces of the robot.。
*
* This function is used to enable or disable the driver of the robot
*
* @param from Specify the operating mode (navigation or joystick)
* @param driver_enable Specify to enable (true) or disable (false) the driver
* @return bool A return of'true` indicates that the operation was successful, and a return of`false' indicates that the operation failed.
*/
bool rcClientInterfaceDriverEnable(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 = true;
bool success = rcClientInterfaceDriverEnable(mode, enable);
if (success) {
std::cout << "Driver Enable Command Successful." << std::endl;
} else {
std::cout << "Failed to Enable Driver." << std::endl;
}
Control Movement Direction and Speed
C++ Interface
rcClientInterfaceDirectionMovement
/**
* @brief Set the instructions for the direction and speed of movement of the robot (front, rear, left, right, and steering).
*
* This function is used to control the direction and speed of movement of the robot.
*
* @param from Specify the mode of operation (navigation or joystick)
* @param rc_direct Specify the direction and speed of movement of the robot.
* @return bool Returns `true` for a successful operation or `false` for a failed operation.
*/
bool rcClientInterfaceDirectionMovement(robot_control::common::NAV_OR_JOY_MODE from,
common::ROBOT_TWIST rc_direct, int64_t time_millis);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
// 获取机器人状态
common::ROBOT_COMMON_STATUS status;
rcClientInterfaceGetCommonStatus(&status);
// 设置以0.5m/s的速度往前行走(示例值)
common::ROBOT_TWIST direction = {{0.5, 0.0, 0.0}, {0.0, 0.0, 0.0}};
bool success = rcClientInterfaceDirectionMovement(mode, direction, status.heartbeat);
if (success) {
std::cout << "Direction Movement Command Successful." << std::endl;
} else {
std::cout << "Failed to Command Direction Movement." << std::endl;
}
Note: For the complete case code, please refer to the Creating a Client Application chapter in the Application Development module.
ROS2 Interface
This interface is used to subscribe to ROS2 /cmd_vel topic to obtain the speed command of the robot movement.
Topic Name | Topic type | role |
---|---|---|
/cmd_vel | geometry_msgs::msg::Twist | subscriber |
Message structure
geometry_msgs::msg::Twist include the following fields:
linear : contains x , y , z , which represents the line speed.
angular : contains x , y , z , which represents the angular velocity.
Sample message
geometry_msgs::msg::Twist twist_msg;
twist_msg.linear.x = 0.1;
twist_msg.linear.y = 0.0;
twist_msg.linear.z = 0.0;
twist_msg.angular.x = 0.0;
twist_msg.angular.y = 0.0;
twist_msg.angular.z = 0.0;
test Method
- publish a one-time message Use the following command to publish a one-time message to
/cmd_vel
topic:
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.1, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"
- continued release of messages Use the following command to continuously publish messages to /cmd_vel topic:
ros2 topic pub --rate 10 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"
Precautions
make sure the ROS2 node is up and subscribing
/cmd_vel
topic.the format of the published message must be strictly geometry_msgs::msg::Twist the definition of the message type.
when continuously publishing messages, pay attention to controlling the publishing frequency to avoid network congestion.
Adjusting Standing Height
C++ Interface
rcClientInterfaceBodyHighAdjust
Introduction
/**
* @brief An interface for adjusting the standing height of the robot.
*
* This function is used to adjust the standing height of the robot.
*
*@param from specifies the operating mode (navigation or joystick).
*@ param scale specifies the proportion of height adjustment. Positive values indicate an increase in height and negative values indicate a decrease in height.
*@return bool return
*/
bool rcClientInterfaceBodyHighAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int height_adjustment = 10; // 示例值,表示增加高度
bool success = rcClientInterfaceBodyHighAdjust(mode, height_adjustment);
if (success) {
std::cout << "Body Height Adjustment Successful." << std::endl;
} else {
std::cout << "Failed to Adjust Body Height." << std::endl;
}
precautions
- ensure that the incoming operation mode and height adjustment scale height_adjustment are integers in the range of 0 to 100.
ROS2 Interface
The service is used to adjust the height of the robot's body.
Service Name | Service type | role |
---|---|---|
/saturn/rc_height_scale | saturn_msgs::srv::HeightScale | client |
request Message
saturn_msgs::srv::HeightScale::Request
the message type contains the following fields:
- scale integer type, representing the Height Scale
sample message
saturn_msgs::srv::HeightScale::Request request;
request.scale = 8;
saturn_msgs::srv::HeightScale::Response response;
Test Method
ros2 service call /saturn/rc_height_scale saturn_msgs/srv/HeightScale "{scale: 8}"
Set the Current Running Scenario
C++ Interface
rcClientInterfaceSetScene
Introduction
/**
* @brief Sets the interface for the current running scene of the robot (stand, down, stairs).
*
* This function is used to set the current running scene of the robot.
*
* @param from Specify the operation mode (navigation or joystick).
* @param scene Specifies the scene type (stand, down, stairs).
* @return bool Returns `true` for a successful setup, `false` for a failed setup.
*/
bool rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE from, common::SCENE_TYPE scene);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
common::SCENE_TYPE scene = common::WALKING; // 示例值,表示站立场景
bool success = rcClientInterfaceSetScene(mode, scene);
if (success) {
std::cout << "Scene Set Successfully." << std::endl;
} else {
std::cout << "Failed to Set Scene." << std::endl;
}
ROS2 Interface
The service is used to adjust the height of the robot's body.
Service Name | Service type | role |
---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | client |
Request Message
ysc_robot_msgs::srv::RobotCommand::Request
the message type contains the following fields:
- command_name string, representing the specific command
sample message
saturn_msgs::srv::HeightScale::Request request;
request.scale = "StairsGait"; //楼梯步态
saturn_msgs::srv::HeightScale::Response response;
test Method
ros2 service call /saturn/robot_command ysc_robot_msgs/srv/Robot_Command "{command_name: 'StairsGait'}"
Demo Mode Control
C++ Interface
rcClientInterfaceDemoControl
Introduction
/**
* @brief Demo mode control.
*
* This function is used to control the robot to enter or exit demo mode.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param mode Specifies the demo mode (2:head shake 3:tail swing 4:wave)
* @param enable Specifies whether to enable demo mode (true means on, false means off).
* @return bool Return `true` for successful control, `false` for failed control.
*/
bool rcClientInterfaceDemoControl(
common::NAV_OR_JOY_MODE from,
int mode,
bool enable);
use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int demo_mode = 2; // 示例值,表示演示模式
bool enable_demo = true; // 示例值,表示开启演示模式
bool success = rcClientInterfaceDemoControl(mode, demo_mode, enable_demo);
if (success) {
std::cout << "Demo Mode Control Set Successfully." << std::endl;
} else {
std::cout << "Failed to Set Demo Mode Control." << std::endl;
}
Precautions
- ensure that the incoming presentation mode and enabled state are valid.
Adjust the Operating Speed
C++ Interface
rcClientInterfaceSpeedAdjust
Introduction
/**
* @brief Interface to regulate the running speed of the robot.
*
* This function is used to adjust the running speed of the robot.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param scale Specifies the scale to adjust the speed (range 1-100).
* @return bool Returns `true` for successful adjustment, `false` for failed.
*/
bool rcClientInterfaceSpeedAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int speed_adjustment = 5; // 示例值,表示增加速度
bool success = rcClientInterfaceSpeedAdjust(mode, speed_adjustment);
if (success) {
std::cout << "Speed Adjustment Successful." << std::endl;
} else {
std::cout << "Failed to Adjust Speed." << std::endl;
}
Software Emergency Stop
C++ Interface
rcClientInterfaceDriverSoftEstop
Introduction
/**
* @brief Software emergency stop interface.
*
* This function is used to trigger the robot to perform a software emergency stop operation.
*
* @param from Specifies the mode of operation (navigation or joystick).
* @return bool Returns `true` for a successful software stop, `false` for a failed one.
*/
bool rcClientInterfaceDriverSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
bool success = rcClientInterfaceDriverSoftEstop(mode);
if (success) {
std::cout << "Soft Estop Command Successful." << std::endl;
} else {
std::cout << "Failed to Command Soft Estop." << std::endl;
}
Recovery Software Emergency Stop
C++ Interface
rcClientInterfacercResumeSoftEstop
Introduction
/**
* @brief Restore software emergency stop interface.
*
* This function is used to trigger the robot to resume the software emergency stop state.
*
* @param from Specifies the mode of operation (navigation or joystick).
* @return bool Returns `true` to indicate that resuming a software emergency stop was successful, `false` to indicate that resuming a software emergency stop failed.
*/
bool rcClientInterfacercResumeSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
Use Case
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
bool success = rcClientInterfacercResumeSoftEstop(mode);
if (success) {
std::cout << "Resume Soft Estop Command Successful." << std::endl;
} else {
std::cout << "Failed to Resume Soft Estop." << std::endl;
}
Set Control Mode
The service sets the mode of controlling the robot, switching to manual or navigation mode.
C++ Interface
rcClientInterfaceSetNavOrJoyControl
Introduction
/**
* @brief Set the navigation control or remote control mode.
*
* This function is used to set the robot to navigation control mode or remote control mode.
*
* @param nav_joy Specifies the control mode (nav or joystick).
* @return bool Returns `true` for a successful setup, `false` for a failed setup.
*/
bool rcClientInterfaceSetNavOrJoyControl(common::NAV_OR_JOY_MODE nav_joy);
Use Case
common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
bool success = rcClientInterfaceSetNavOrJoyControl(mode);
if (success) {
std::cout << "Nav or Joy Control Set Successfully." << std::endl;
} else {
std::cout << "Failed to Set Nav or Joy Control." << std::endl;
}
Precautions
ensure that the incoming control mode is valid.
set robot pose
ROS2 Interface
Service Name | Service type | role |
---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | client |
request Message
ysc_robot_msgs::srv::RobotCommand::Request
The message type contains the following fields:
command_name
String, representing the specific commandEnableNavigation
Indicates the navigation modeEnableTeleoption
Indicates the lever control mode.
Sample message
saturn_msgs::srv::HeightScale::Request request;
request.scale = "EnableNavigation"; //导航
saturn_msgs::srv::HeightScale::Response response;
Test Method
ros2 service call /saturn/rc_nav_or_manual saturn_msgs/srv/NavOrManual "{command_name: 'EnableNavigation'}"