xpkg_carrier Interface Description
Payload Carrier Interface
Public APIs
Publish
Topic | Msg Type | Description |
---|---|---|
/carrier_state |
nav_msgs/Odometry |
Publish current carrier state |
Subscribe
Topic | Msg Type | Description |
---|---|---|
/carrier_cmd_vel |
geometry_msgs/TwistStamped |
Subscribe to target carrier velocity |
/carrier_cmd_pos |
geometry_msgs/PoseStamped |
Subscribe to target carrier pose |
Parameter
Name | Data Type | Description |
---|---|---|
carrier_limit_vel_z |
double |
The limitation of the speed, for both rising and falling. The unit is meters per second ($m/s$) |
Detailed Description
/carrier_state
This topic publishes the current state of the payload carrier.
/carrier_cmd_vel
This topic receives the target velocity of the payload carrier.
-
Type:
geometry_msgs/TwistStamped
std_msgs/Header header uint32 seq time stamp string frame_id geometry_msgs/Twist twist geometry_msgs/Vector3 linear float64 x float64 y float64 z geometry_msgs/Vector3 angular float64 x float64 y float64 z
-
Usage:
-
header
-
stamp
is the timestamp of the message -
frame_id
is the base link of the chassis, typicallybase_link
-
-
twist
- The target velocity of the carrier (only for velocity control mode)
- The
twist.linear.z
indicates the rising speed of the carrier (negative values indicate falling) - Unit: meters per second ($m/s$)
-
-
Example:
msg = geometry_msgs.msg.TwistStamped() msg.header.stamp = rospy.Time.now() msg.header.frame_id = "base_link" msg.twist.linear.z = 0.2
/carrier_cmd_pos
This topic receives the target pose of the payload carrier.
-
Type:
geometry_msgs/PoseStamped
std_msgs/Header header uint32 seq time stamp string frame_id geometry_msgs/Pose pose geometry_msgs/Point position float64 x float64 y float64 z geometry_msgs/Quaternion orientation float64 x float64 y float64 z float64 w
-
Usage:
-
header
-
stamp
is the timestamp of the message -
frame_id
is the base link of the chassis, typicallybase_link
-
-
pose
- The target pose of the carrier (only for position control mode)
- The
pose.position.z
indicates the height of the carrier - Unit: meters ($m$)
-
-
Example:
msg = geometry_msgs.msg.PoseStamped() msg.header.stamp = rospy.Time.now() msg.header.frame_id = "base_link" msg.pose.position.z = 0.2