High-Level Motion Service Interfaces
Introduction
The high-level control interface allows the Daystar Robot to execute motion commands such as velocity control and posture control by calling ROS 2 Topics, ROS 2 Services, or C++ functions.
Function | C++ | ROS |
---|---|---|
Enable/Disable Drive | ✔ | |
Control Movement Direction/Speed | ✔ | ✔ |
Adjust Standing Height | ✔ | ✔ |
Set Current Operating Scene | ✔ | ✔ |
Demo Mode Control | ✔ | |
Adjust Running Speed | ✔ | |
Software Emergency Stop | ✔ | |
Resume from Emergency Stop | ✔ | |
Set Control Mode | ✔ | ✔ |
Enable/Disable Drive
C++ Interface
Function: rcClientInterfaceDriverEnable
/**
* @brief Interface to enable or disable robot drive.
*
* This function enables or disables the robot's actuator drive.
*
* @param from Specifies the control mode (navigation or joystick).
* @param driver_enable Set to `true` to enable the drive, or `false` to disable it.
* @return bool Returns `true` if the command succeeds, `false` otherwise.
*/
bool rcClientInterfaceDriverEnable(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 = 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
Function: rcClientInterfaceDirectionMovement
/**
* @brief Sends motion commands to set the robot’s movement direction and speed (forward, backward, lateral, and turning).
*
* This function is used to control the robot's movement direction and velocity.
*
* @param from Specifies the control mode (navigation or joystick).
* @param rc_direct Specifies the desired movement direction and speed.
* @param time_millis Timestamp for the command, typically obtained from robot status heartbeat.
* @return bool Returns `true` if the command is successfully sent, `false` otherwise.
*/
bool rcClientInterfaceDirectionMovement(robot_control::common::NAV_OR_JOY_MODE from,
common::ROBOT_TWIST rc_direct, int64_t time_millis);
Usage Example
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
// Retrieve robot status
common::ROBOT_COMMON_STATUS status;
rcClientInterfaceGetCommonStatus(&status);
// Command the robot to move forward at 0.5 m/s (example value)
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;
}
ROS2 Interface
This interface is used to subscribe to the ROS2 /cmd_vel
topic in order to receive robot motion velocity commands.
Topic Name | Topic Type | Role |
---|---|---|
/cmd_vel | geometry_msgs::msg::Twist | Subscriber |
Message Structure
The geometry_msgs::msg::Twist
message contains the following fields:
- linear: includes
x
,y
,z
, representing linear velocity. - angular: includes
x
,y
,z
, representing angular velocity.
Example 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;
Testing Methods
- Publish a one-time message Use the following command to publish a single message to the
/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}}"
- Publish messages continuously Use the following command to continuously publish messages to
/cmd_vel
at a rate of 10 Hz:
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
- Ensure the ROS2 node is launched and actively subscribed to the
/cmd_vel
topic. - The message format must strictly comply with the
geometry_msgs::msg::Twist
message definition. - When publishing at a fixed rate, make sure to control the frequency to avoid network congestion.
Adjusting Standing Height
C++ Interface
Function: rcClientInterfaceBodyHighAdjust
/**
* @brief Interface for adjusting the robot's standing height.
*
* This function adjusts the robot's body height.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param scale Specifies the height adjustment scale. Positive values increase height; negative values decrease it.
* @return bool Returns `true` if adjustment is successful; otherwise returns `false`.
*/
bool rcClientInterfaceBodyHighAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
Usage Example:
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int height_adjustment = 10; // Example value: increase height
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 operation mode and
height_adjustment
value are valid. - The
scale
should be an integer within the range of 0 to 100.
ROS2 Interface
This service is used to adjust the robot's body height.
Service Name | Service Type | Role |
---|---|---|
/saturn/rc_height_scale | saturn_msgs::srv::HeightScale | Client |
Request Message
saturn_msgs::srv::HeightScale::Request
contains the following field:
scale
: Integer type, indicating the target height scale.
Example Message
saturn_msgs::srv::HeightScale::Request request;
request.scale = 8;
saturn_msgs::srv::HeightScale::Response response;
Testing Method
ros2 service call /saturn/rc_height_scale saturn_msgs/srv/HeightScale "{scale: 8}"
Setting Current Operating Scene
C++ Interface
Function: rcClientInterfaceSetScene
/**
* @brief Interface for setting the robot's current operating scene (e.g., standing, lying down, stairs).
*
* This function sets the current operating scene of the robot.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param scene Specifies the scene type (e.g., standing, lying, stairs).
* @return bool Returns `true` if the scene is successfully set; otherwise returns `false`.
*/
bool rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE from, common::SCENE_TYPE scene);
Usage Example:
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
common::SCENE_TYPE scene = common::WALKING; // Example value: standing scene
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
This service is used to set the robot's current operational scene (e.g., StairsGait, StandingPose).
Service Name | Service Type | Role |
---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | Client |
请求消息
ysc_robot_msgs::srv::RobotCommand::Request
includes the following field:
command_name
: A string representing the specific command (e.g., "StairsGait").
Request Message
saturn_msgs::srv::HeightScale::Request request;
request.scale = "StairsGait"; //StairsGait
saturn_msgs::srv::HeightScale::Response response;
Testing Method
ros2 service call /saturn/robot_command ysc_robot_msgs/srv/Robot_Command "{command_name: 'StairsGait'}"
Demonstration Mode Control
C++ Interface
Function: rcClientInterfaceDemoControl
/**
* @brief Demonstration mode control.
*
* This function is used to enable or disable the robot's demonstration mode.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param mode Specifies the demonstration mode:
* 2 - Head Shaking,
* 3 - Tail Waving,
* 4 - Hand Waving.
* @param enable Specifies whether to enable the demo mode (true to enable, false to disable).
* @return bool Returns `true` if the operation is successful; otherwise returns `false`.
*/
bool rcClientInterfaceDemoControl(
common::NAV_OR_JOY_MODE from,
int mode,
bool enable);
Usage Example
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int demo_mode = 2; // Example: head shaking
bool enable_demo = true; // Example: enable demo mode
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;
}
Notes
- Ensure that the input
mode
is within the valid demonstration mode range (e.g., 2, 3, or 4). - Make sure the
enable
parameter is explicitly set totrue
orfalse
.
Adjust Running Speed
C++ Interface
Function: rcClientInterfaceSpeedAdjust
/**
* @brief Interface for adjusting the robot's running speed.
*
* This function is used to adjust the robot's operational speed.
*
* @param from Specifies the operation mode (navigation or joystick).
* @param scale Specifies the speed adjustment scale (range: 1–100).
* @return bool Returns `true` if the adjustment is successful; otherwise returns `false`.
*/
bool rcClientInterfaceSpeedAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
Usage Example
robot_control::common::NAV_OR_JOY_MODE mode = robot_control::common::NAV_OR_JOY_MODE::joy_control;
int speed_adjustment = 5; // Example value indicating increased speed
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
Function: rcClientInterfaceDriverSoftEstop
/**
* @brief Software emergency stop interface.
*
* This function is used to trigger a software-based emergency stop on the robot.
*
* @param from Specifies the operation mode (navigation or joystick).
* @return bool Returns `true` if the emergency stop was successfully triggered; otherwise returns `false`.
*/
bool rcClientInterfaceDriverSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
Usage Example
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;
}
Resume Software Emergency Stop
C++ Interface
Function: rcClientInterfacercResumeSoftEstop
/**
* @brief Resume software emergency stop interface.
*
* This function is used to resume the robot from the software emergency stop state.
*
* @param from Specifies the operation mode (navigation or joystick).
* @return bool Returns `true` if the resume command was successful; otherwise returns `false`.
*/
bool rcClientInterfacercResumeSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
Usage Example
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
This service sets the robot's control mode, allowing switching between manual control (via joystick) and autonomous navigation.
C++ Interface
Function: rcClientInterfaceSetNavOrJoyControl
/**
* @brief Set navigation or joystick control mode.
*
* This function sets the robot to either navigation mode or joystick/manual control mode.
*
* @param nav_joy Specifies the control mode (navigation or joystick).
* @return bool Returns `true` if the mode is set successfully; otherwise returns `false`.
*/
bool rcClientInterfaceSetNavOrJoyControl(common::NAV_OR_JOY_MODE nav_joy);
Usage Example:
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;
}
Notes:
- Ensure the specified control mode is valid.
- This interface is typically used in scenarios where the robot needs to switch between autonomous and manual control.
ROS2 Interface
Service Name | Service Type | Role |
---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | Client |
Request Fields (ysc_robot_msgs::srv::RobotCommand::Request
):
command_name
:string
EnableNavigation
for autonomous navigation modeEnableTeleoption
for joystick/manual control mode
Example Message:
saturn_msgs::srv::HeightScale::Request request;
request.scale = "EnableNavigation"; //Switch to navigation mode
saturn_msgs::srv::HeightScale::Response response;
Test Command
ros2 service call /saturn/rc_nav_or_manual saturn_msgs/srv/NavOrManual "{command_name: 'EnableNavigation'}"