Segway-Ninebot RmpLite220

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 a DifferentialBaseState composite message.

  • Ego Motion Data: The current robot odometry. This is a DifferentialBaseEgoMotion composite message.

  • IMU Data: The current chassis IMU data. This is an Imu message.

  • Wheel Ticks: The current wheel encoder ticks. This is an EnocderTicks message.

The following example uses the robot remote control module to drive the robot.

Copy
Copied!
            

--- 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

Encoder Data Transmitter

lookup_name

tx_encoder_ticks

description

Current wheel encoder data

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Imu Data

lookup_name

tx_imu

description

Current differential drive robot imu data

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Ego Motion Data

lookup_name

tx_ego_motion

description

Current estimate of robot pose

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Battery State Transmitter

lookup_name

tx_battery_state

description

Current battery state

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Command

lookup_name

rx_command

description

Target differential drive robot state from controller

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Memory allocator

lookup_name

allocator

description

Handle to the memory allocator pool used for output messages

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Load State

lookup_name

load_state

description

Load state of chassis. 0: no_load, 1: full_load

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_INT32

default

0

name

Flip Orientation

lookup_name

flip_orientation

description

Whether to flip the forward direction of the base

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_BOOL

default

False

name

Speed Limit Foward

lookup_name

speed_limit_linear

description

Maximum linear speed allowed to travel at (m/s)

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

1.1

name

Speed Limit Angular

lookup_name

speed_limit_angular

description

Maximum angular speed allowed to rotate at (rad/s)

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

1.0

name

Hang Mode

lookup_name

hang_mode

description

Hang mode of chassis. 0: off, 1: on

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_INT32

default

0

name

Handle to atlas frontend to access the composite schema server

lookup_name

atlas_frontend

description

N/A

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Segway IMU Frame

lookup_name

segway_imu_frame

description

PoseTreeID for IMU data from the segway imu.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Segway Ego Motion Child Frame

lookup_name

segway_ego_motion_child_frame

description

PoseTreeID for ego motion data from the segway.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

nvidia::isaac::DifferentialBaseVelocityEstimator

Estimates the velocity of a differential drive robot with encoder data

Parameters:

name

State Transmitter

lookup_name

tx_state

description

Current differential drive robot state

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Encoder Tick Receiver

lookup_name

rx_encoder_ticks

description

Encoder ticks from differential drive robot

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Handle to atlas frontend to access the composite schema server

lookup_name

atlas_frontend

description

N/A

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Memory allocator

lookup_name

allocator

description

Handle to the memory allocator pool used for output messages

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Wheelbase State Frame

lookup_name

wheelbase_state_frame

description

PoseTreeID for wheelbase data from the data.

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_HANDLE

default

N/A

name

Ticks Per Revolution

lookup_name

k_ticks_per_revolution

description

Number of encoder ticks per revolution

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_INT32

default

4096

name

Wheel Track Width

lookup_name

k_wheel_track_width_m

description

Distance between wheels in Meters

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

0.413

name

Wheel Diameter

lookup_name

k_wheel_diameter_m

description

Diameter of wheels in Meters

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

0.28

name

Cut Off Frequency

lookup_name

k_cut_off_frequency_radps

description

Cut off frequency for the low pass filter in rad/s

flags

GXF_PARAMETER_FLAGS_NONE

type

GXF_PARAMETER_TYPE_FLOAT64

default

50.26548245743669

© Copyright 2018-2023, NVIDIA Corporation. Last updated on Oct 23, 2023.