The RMPLite220 is a differential drive robot from Segway-Ninebot. This driver provides a GXF interface for the hardware. It accepts a differential base control input, and publishes the robot state, odometry information, and IMU data.
Command*: The base control command. This is a differential drive command with the desired linear speed in m/s, and desired angular speed in rad/s. The command is a `DifferentialBaseCommand
composite message.
State
: The current robot state . This is aDifferentialBaseState
composite message.Ego Motion Data
: The current robot odometry. This is aDifferentialBaseEgoMotion
composite message.IMU Data
: The current chassis IMU data. This is anImu
message.Wheel Ticks
: The current wheel encoder ticks. This is anEnocderTicks
message.
The following example uses the robot remote control module to drive the robot.
---
name: atlas
components:
- name: frontend
type: nvidia::isaac::AtlasFrontend
parameters:
pose_tree: pose_tree
composite_schema_server: composite_schema_server
- name: pose_tree
type: nvidia::isaac::PoseTree
- name: pose_tree_setup
type: nvidia::isaac::PoseTreeSetup
parameters:
pose_tree: pose_tree
- name: composite_schema_server
type: nvidia::isaac::CompositeSchemaServer
- name: segway_imu_frame
type: nvidia::isaac::PoseTreeFrame
parameters:
pose_tree: pose_tree
- name: segway_wheelbase_state_frame
type: nvidia::isaac::PoseTreeFrame
parameters:
pose_tree: pose_tree
- name: segway_ego_motion_child_frame
type: nvidia::isaac::PoseTreeFrame
parameters:
pose_tree: pose_tree
---
name: remote_control_segway
components:
- name: subgraph
type: nvidia::gxf::Subgraph
parameters:
location: "apps/amr/robot_remote_control/robot_remote_control_segway.subgraph.yaml"
prerequisites:
atlas: atlas/frontend
segway_imu_frame: atlas/segway_imu_frame
segway_wheelbase_state_frame: atlas/segway_wheelbase_state_frame
segway_ego_motion_child_frame: atlas/segway_ego_motion_child_frame
---
name: scheduler
components:
- name: scheduler
type: nvidia::gxf::GreedyScheduler
parameters:
clock: clock
- name: clock
type: nvidia::gxf::RealtimeClock
NvIsaacSegwayExtension
Extension to interface with Segway chassis
nvidia::isaac::SegwayDriver
Interfaces with a Segway chassis to send commands and query data
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
Encoder Data Transmitter
tx_encoder_ticks
Current wheel encoder data
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Imu Data
tx_imu
Current differential drive robot imu data
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Ego Motion Data
tx_ego_motion
Current estimate of robot pose
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Battery State Transmitter
tx_battery_state
Current battery state
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Command
rx_command
Target differential drive robot state from controller
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Memory allocator
allocator
Handle to the memory allocator pool used for output messages
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Load State
load_state
Load state of chassis. 0: no_load, 1: full_load
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_INT32
0
- name
- lookup_name
- description
- flags
- type
- default
Flip Orientation
flip_orientation
Whether to flip the forward direction of the base
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_BOOL
False
- name
- lookup_name
- description
- flags
- type
- default
Speed Limit Foward
speed_limit_linear
Maximum linear speed allowed to travel at (m/s)
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
1.1
- name
- lookup_name
- description
- flags
- type
- default
Speed Limit Angular
speed_limit_angular
Maximum angular speed allowed to rotate at (rad/s)
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
1.0
- name
- lookup_name
- description
- flags
- type
- default
Hang Mode
hang_mode
Hang mode of chassis. 0: off, 1: on
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_INT32
0
- name
- lookup_name
- description
- flags
- type
- default
Handle to atlas frontend to access the composite schema server
atlas_frontend
N/A
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Segway IMU Frame
segway_imu_frame
PoseTreeID for IMU data from the segway imu.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Segway Ego Motion Child Frame
segway_ego_motion_child_frame
PoseTreeID for ego motion data from the segway.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
nvidia::isaac::DifferentialBaseVelocityEstimator
Estimates the velocity of a differential drive robot with encoder data
Parameters:
- name
- lookup_name
- description
- flags
- type
- default
State Transmitter
tx_state
Current differential drive robot state
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Encoder Tick Receiver
rx_encoder_ticks
Encoder ticks from differential drive robot
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Handle to atlas frontend to access the composite schema server
atlas_frontend
N/A
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Memory allocator
allocator
Handle to the memory allocator pool used for output messages
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Wheelbase State Frame
wheelbase_state_frame
PoseTreeID for wheelbase data from the data.
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_HANDLE
N/A
- name
- lookup_name
- description
- flags
- type
- default
Ticks Per Revolution
k_ticks_per_revolution
Number of encoder ticks per revolution
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_INT32
4096
- name
- lookup_name
- description
- flags
- type
- default
Wheel Track Width
k_wheel_track_width_m
Distance between wheels in Meters
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
0.413
- name
- lookup_name
- description
- flags
- type
- default
Wheel Diameter
k_wheel_diameter_m
Diameter of wheels in Meters
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
0.28
- name
- lookup_name
- description
- flags
- type
- default
Cut Off Frequency
k_cut_off_frequency_radps
Cut off frequency for the low pass filter in rad/s
GXF_PARAMETER_FLAGS_NONE
GXF_PARAMETER_TYPE_FLOAT64
50.26548245743669