Project

General

Profile

rmp440-genom3

Genom3 component to control the Segway RMP440 platform.

The rmp444-genom3 component provides two main activities :

  • Track - to control the robot’s speed through a Genom3 port

  • Joystick - to control the robot’s speed through a Joystick.

Activities

Init

This activity initializes the component. There is one string parameter to specify the connection to the robot to be used. Generally, in the robots default configuration it is “10.40.40.40:8080” to specify an ethernet connection, with the robot having the IP address 10.40.40.40 and a port of 8080.

Track

This activity starts the speed tracking. It has no parameter, but expects an inport port cmd_vel to be provided. It should have the or::genpos::cart_speed type (defined in genpos.idl).

Joystick

This request uses a joystick to control the robot. The input port Joystick should be provided by the joystick-genom3 component.

Gyro

This request controls the gyroscope (when present). The rmp440-genom3 component supports various Fiber-optics gyroscopes.

Parameters are :

  • mode : the operation mode of the gyroscope which can be :

    • gyro_off (0) - the gyroscope is ignored

    • gyro_on_if_motion (1) - the gyroscope is used only while the robot is moving

    • gyro_on (2) - the gyroscope is always active. If the gyroscope is always active and its measurment is drifting for some reason, it will cause the robot to rotate to compensate for this drift, event when the angular speed command is zero.

  • port : the device name corresponding to the port to which the gyro is connected. Typically something like /dev/ttyS4 for serial port gyroscopes.

  • type : the device type, passed to gyrlLib. Currently supported device types include:

    • GYRO_KVH_ECORE_1000 (1)

    • GYRO_KVH_DSP_5000 (2)

    • GYRO_KVH_DSP_3000 (3)

  • latitude : an approximation of the current latitude of the robot to compensate for earth rotation.

  • woffset : an additional offset added to the angular speed rotation that may be added to compensate for measurement drifts that cannot be compensated otherwise.

JoystickOn

This is the joystick tracking activity. It expects an input port of type or_joystick::state, typically provided by the joystick-genom3 component.

functions

Stop

This function interrupts Track or JoystickOn activities, setting the speed references to zero.

log

Starts logging of internal robot parameters to a file

log_stop

Stops logging of internal robots parameters

Output Ports

Pose

or_pose_estimator::state structure representing the current position and speed of the robot.

Status

The internal state of the Segway micro-controller

StatusGeneric

An abstracted version of the above (common to several Genom3 components for different robots)

Using the component

With ROS on the command line

  • initialisation

$ rosaction call Init 10.40.40.40:8080
  • setting up the gyroscope

$ rosaction call Gyro { 1 /dev/ttyS4 3 43 0 }
  • starting a tracking

$ rosaction call Track {}
  • A small cmd_vel provider

import rospy

from rmp440.msg import or_genpos_cart_speed

def talker():
    pub = rospy.Publisher('ttrack', or_genpos_cart_speed, queue_size=20)
    rospy.init_node('ttrack', anonymous=True)
    rate = rospy.Rate(20)       = 20Hz
    ref = or_genpos_cart_speed(v = 0.0, vt = 0.0, w = 0.0,
                               vmax = 0.5, wmax = 0.5,
                               linAccelMax = 0.9,
                               angAccelMax = 0.9,
                               updatePeriod = 50)
    while not rospy.is_shutdown():
        ref.numRef = ref.numRef + 1;
        pub.publish(ref)
        rate.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass

With Genomix

the following Tcl code will setup a the connection of the rmp440-genom3 component and a Joystick (using joystick-genom3):

package require genomix
set g [genomix::connect localhost]
$g rpath /home/matthieu/dev/x86_64-ubuntu/lib/genom/pocolibs/plugins

$g load rmp440
$g load joystick

proc setup {} {
    if {[namespace exists rmp440]} {
        if {[namespace exists joystick]} {
            ::rmp440::connect_port
            { local Joystick remote joystick/device/Logitech }
        }
        rmp440::Init 10.40.40.40:8080
        ::rmp440::Gyro {params {
            mode ::rmp440::gyro_on_if_motion
            port /dev/ttyS4
            type ::GYRO_KVH_DSP_3000
            latitude 45
            woffset 0}}
    }
}