Public Member Functions | Private Member Functions | Private Attributes | List of all members
segwayrmp::SegwayRMP Class Reference

#include <segwayrmp.h>

Public Member Functions

void configureSerial (std::string port, int baudrate=460800)
 
void configureUSBByDescription (std::string description, int baudrate=460800)
 
void configureUSBByIndex (int device_index, int baudrate=460800)
 
void configureUSBBySerial (std::string serial_number, int baudrate=460800)
 
void connect (bool reset_integrators=true)
 
void move (float linear_velocity, float angular_velocity)
 
void moveCounts (short int linear_counts, short int angular_counts)
 
void resetAllIntegrators ()
 
 SegwayRMP (InterfaceType interface_type=serial, SegwayRMPType segway_rmp_type=rmp200)
 
void setBalanceModeLocking (bool state=true)
 
void setControllerGainSchedule (ControllerGainSchedule controller_gain_schedule)
 
void setCurrentLimitScaleFactor (double scalar=1.0)
 
void setExceptionCallback (ExceptionCallback callback)
 
void setLogMsgCallback (std::string log_level, LogMsgCallback callback)
 
void setMaxAccelerationScaleFactor (double scalar=1.0)
 
void setMaxTurnScaleFactor (double scalar=1.0)
 
void setMaxVelocityScaleFactor (double scalar=1.0)
 
void setOperationalMode (OperationalMode operational_mode)
 
void setStatusCallback (SegwayStatusCallback callback)
 
void setTimestampCallback (GetTimeCallback callback)
 
void shutdown ()
 
 ~SegwayRMP ()
 

Private Member Functions

void ExecuteCallbacks_ ()
 
void operator= (const SegwayRMP &)
 
const SegwayRMPoperator= (SegwayRMP)
 
bool ParsePacket_ (Packet &packet, SegwayStatus::Ptr &ss_ptr)
 
void ProcessPacket_ (Packet &packet)
 
void ReadContinuously_ ()
 
void SetConstantsBySegwayType_ (SegwayRMPType &rmp_type)
 
void StartReadingContinuously_ ()
 
void StopReadingContinuously_ ()
 

Private Attributes

boost::thread callback_execution_thread_
 
bool connected_
 
bool continuously_reading_
 
LogMsgCallback debug_
 
double dps_to_counts_
 
LogMsgCallback error_
 
GetTimeCallback get_time_
 
ExceptionCallback handle_exception_
 
LogMsgCallback info_
 
InterfaceType interface_type_
 
double meters_to_counts_
 
double mps_to_counts_
 
boost::thread read_thread_
 
double rev_to_counts_
 
RMPIOrmp_io_
 
SegwayRMPType segway_rmp_type_
 
SegwayStatus::Ptr segway_status_
 
FiniteConcurrentSharedQueue< SegwayStatusss_queue_
 
SegwayStatusCallback status_callback_
 
double torque_to_counts_
 

Detailed Description

Provides an interface for the Segway RMP.

Definition at line 336 of file segwayrmp.h.

Constructor & Destructor Documentation

SegwayRMP::SegwayRMP ( InterfaceType  interface_type = serial,
SegwayRMPType  segway_rmp_type = rmp200 
)

Constructs the SegwayRMP object given the interface type.

Parameters
interface_typeThis must be can, usb, or serial. Default is usb.
segway_rmp_typeThis can be rmp50, rmp100, rmp200, or rmp400. Default is rmp200.

Definition at line 219 of file segwayrmp.cc.

SegwayRMP::~SegwayRMP ( )

Definition at line 264 of file segwayrmp.cc.

Member Function Documentation

void SegwayRMP::configureSerial ( std::string  port,
int  baudrate = 460800 
)

Configures the serial interface, if the library is built with serial support, otherwise throws ConfigurationException.

Parameters
portDefines which serial port to connect to in serial mode.
baudrateDefines the speed of the serial port in baud's. Defaults to 460800 (recommended).

Definition at line 281 of file segwayrmp.cc.

void SegwayRMP::configureUSBByDescription ( std::string  description,
int  baudrate = 460800 
)

Configures the FTD2XX usb interface, if the library is built with usb support, otherwise throws ConfigurationException.

Parameters
descriptionDefines which usb port to connect to based on the devices description.
baudrateDefines the speed of the usb port in baud's. Defaults to 460800 (recommended).

Definition at line 308 of file segwayrmp.cc.

void SegwayRMP::configureUSBByIndex ( int  device_index,
int  baudrate = 460800 
)

Configures the FTD2XX usb interface, if the library is built with usb support, otherwise throws ConfigurationException.

Parameters
device_indexDefines which usb port to connect to based on the devices index. Note: This is indexed by all ftd2xx devices on the system.
baudrateDefines the speed of the usb port in baud's. Defaults to 460800 (recommended).

Definition at line 320 of file segwayrmp.cc.

void SegwayRMP::configureUSBBySerial ( std::string  serial_number,
int  baudrate = 460800 
)

Configures the FTD2XX usb interface, if the library is built with usb support, otherwise throws ConfigurationException.

Parameters
serial_numberDefines which usb port to connect to based on the devices serial number.
baudrateDefines the speed of the usb port in baud's. Defaults to 460800 (recommended).

Definition at line 297 of file segwayrmp.cc.

void SegwayRMP::connect ( bool  reset_integrators = true)

Connects to the Segway. Ensure it has been configured first.

Parameters
reset_integratorsIf this is true, the integrators are reset.

Definition at line 331 of file segwayrmp.cc.

void SegwayRMP::ExecuteCallbacks_ ( )
private

Definition at line 761 of file segwayrmp.cc.

void SegwayRMP::move ( float  linear_velocity,
float  angular_velocity 
)

This command moves the base at a given linear and angular velocity. This assumes the max velocity scalar is set to 1.0.

Parameters
linear_velocityForward/Reverse desired velocity of the vehicle in m/s.
angular_velocityDesired angular velocity of the vehicle in degrees/s, positive to is left.

Definition at line 394 of file segwayrmp.cc.

void SegwayRMP::moveCounts ( short int  linear_counts,
short int  angular_counts 
)

This command moves the base at a given linear and angular count.

Parameters
linear_countsForward/Reverse effort, in range [-1176, 1176]. Which maps approximately to [-8, 8] mph (assuming a max velocity scalar of 1.0)
angular_countsAngular effort, in range [-1024, 1024].

Definition at line 367 of file segwayrmp.cc.

void segwayrmp::SegwayRMP::operator= ( const SegwayRMP )
private
const SegwayRMP& segwayrmp::SegwayRMP::operator= ( SegwayRMP  )
private
bool SegwayRMP::ParsePacket_ ( Packet packet,
SegwayStatus::Ptr ss_ptr 
)
private

Definition at line 830 of file segwayrmp.cc.

void SegwayRMP::ProcessPacket_ ( Packet packet)
private

Definition at line 933 of file segwayrmp.cc.

void SegwayRMP::ReadContinuously_ ( )
private

Definition at line 744 of file segwayrmp.cc.

void SegwayRMP::resetAllIntegrators ( )

Resets all of the integrators.

Todo:
Add individual functions for reseting each integrator.

Definition at line 522 of file segwayrmp.cc.

void SegwayRMP::setBalanceModeLocking ( bool  state = true)

Locks or unlocks the balancing mode.

Parameters
stateThis allows you to specify whether you want lock or unlock balancing mode. True for locked and False for unlocked. The default state is True.

Definition at line 491 of file segwayrmp.cc.

void SegwayRMP::SetConstantsBySegwayType_ ( SegwayRMPType rmp_type)
private

Definition at line 795 of file segwayrmp.cc.

void SegwayRMP::setControllerGainSchedule ( ControllerGainSchedule  controller_gain_schedule)

Sets the controller gain schedule.

Parameters
controller_gain_scheduleThis sets the contoller gain schedule, possible values are light, tall, and heavy.

Definition at line 455 of file segwayrmp.cc.

void SegwayRMP::setCurrentLimitScaleFactor ( double  scalar = 1.0)

Sets the Current Limit Scale Factor

Parameters
scalarThis is a value between 0.0 and 1.0 which will set the current limit for the drive motors, limiting torque. Values larger than 1.0 will round down to 1.0 and values < 0 will round up to 0.0. Parameter defaults to 1.0.

Definition at line 677 of file segwayrmp.cc.

void SegwayRMP::setExceptionCallback ( ExceptionCallback  callback)

Sets the Callback Function to be called on when an unhandled exception occurs.

This allows you to catch and handle otherwise unhandled exceptions that might occur in an internal thread to the segwayrmp library.

The provided function must follow this prototype:

   void yourExceptionCallback(const std::exception&)

Here is an example:

   SegwayTime yourTimestampCallback() {
       std::cerr << "SegwayRMP Unhandled Exception: " << error.what()
                 << std::endl;
   }

And the resulting call to make it the callback:

   segwayrmp::SegwayRMP my_segway_rmp;
   my_segway_rmp.setExceptionCallback(yourExceptionCallback);

Alternatively you can use a class method as a callback using boost::bind:

   #include <boost/bind.hpp>
   #include <ctime>
   #include "segwayrmp.h"
   class MySegwayWrapper
   {
   public:
    MySegwayWrapper () {
      my_segway_rmp.setExceptionCallback(
        boost::bind(&MySegwayWrapper::handleException, this, _1));
    }
    SegwayTime handleException() {
       std::cerr << "SegwayRMP Unhandled Exception: " << error.what()
                 << std::endl;
    }
   private:
    segwayrmp::SegwayRMP my_segway_rmp;
   };
Parameters
callbackA function pointer to the callback to handle otherwise unhandled exceptions that occur.

Definition at line 740 of file segwayrmp.cc.

void SegwayRMP::setLogMsgCallback ( std::string  log_level,
LogMsgCallback  callback 
)

Sets the Callback Function to be called when a log message occurs.

This allows you to hook into the message reporting of the library and use your own logging facilities.

The provided function must follow this prototype:

   void yourLogMsgCallback(const std::string &msg)

Here is an example (Using Debug in this case):

   void yourDebugMsgCallback(const std::string &msg) {
       std::cerr << "SegwayRMP Debug: " << msg << std::endl;
   }

And the call to make it the callback (Again using Debug for example):

   segwayrmp::SegwayRMP my_segway_rmp;
   my_segway_rmp.setLogMsgCallback("debug", yourDebugMsgCallback);

Alternatively you can use a class method as a callback using boost::bind:

   #include <boost/bind.hpp>
   #include "segwayrmp.h"
   class MySegwayWrapper
   {
   public:
    MySegwayWrapper () {
     my_segway_rmp.setLogMsgCallback("debug"
       boost::bind(&MySegwayWrapper::handleDebugMsg, this, _1));
    }
    void handleDebugMsg(const std::string &msg) {
      std::cerr << "SegwayRMP Debug: " << msg << std::endl;
    }
   private:
    segwayrmp::SegwayRMP my_segway_rmp;
   };
Parameters
log_levelA std::string which indicates which log level to assign a callback to. Must be one of "debug", "info", or "error".
callbackA LogMsgCallback type function which will be called when a log of level log_level occurs.

Definition at line 719 of file segwayrmp.cc.

void SegwayRMP::setMaxAccelerationScaleFactor ( double  scalar = 1.0)

Sets the Max Acceleration Scale Factor

Parameters
scalarThis is a value between 0.0 and 1.0 which will set the acceleration scale factor on the segway internally for all velocity commands. Values larger than 1.0 will round down to 1.0 and values < 0 will round up to 0.0. Parameter defaults to 1.0.

Definition at line 601 of file segwayrmp.cc.

void SegwayRMP::setMaxTurnScaleFactor ( double  scalar = 1.0)

Sets the Max Turn Scale Factor

Parameters
scalarThis is a value between 0.0 and 1.0 which will set the scale factor on the segway internally for all turn commands. Values larger than 1.0 will round down to 1.0 and values < 0 will round up to 0.0. Parameter defaults to 1.0.

Definition at line 639 of file segwayrmp.cc.

void SegwayRMP::setMaxVelocityScaleFactor ( double  scalar = 1.0)

Sets the Max Velocity Scale Factor

Parameters
scalarThis is a value between 0.0 and 1.0 which will set the scale factor on the segway internally for all velocity commands. Values larger than 1.0 will round down to 1.0 and values < 0 will round up to 0.0. Parameter defaults to 1.0.

Definition at line 563 of file segwayrmp.cc.

void SegwayRMP::setOperationalMode ( OperationalMode  operational_mode)

Sets the operational mode.

Parameters
operational_modeThis must be disabled, tractor, or balanced.

Definition at line 422 of file segwayrmp.cc.

void SegwayRMP::setStatusCallback ( SegwayStatusCallback  callback)

Sets the Callback Function to be called on new Segway Status Updates.

The provided function must follow this prototype:

   void yourSegwayStatusCallback(segwayrmp::SegwayStatus &segway_status)

Here is an example:

   void handleSegwayStatus(segwayrmp::SegwayStatus &ss) {
       std::cout << ss.str() << std::endl << std::endl;
   }

And the resulting call to make it the callback:

   segwayrmp::SegwayRMP my_segway_rmp;
   my_segway_rmp.setStatusCallback(handleSegwayStatus);

Alternatively you can use a class method as a callback using boost::bind:

   #include <boost/bind.hpp>
   #include "segwayrmp.h"
   class MySegwayWrapper
   {
   public:
    MySegwayWrapper () {
     my_segway_rmp.setStatusCallback(
       boost::bind(&MySegwayWrapper::handleSegwayStatus, this, _1));
    }
    void handleSegwayStatus(segwayrmp::SegwayStatus &ss) {
      std::cout << ss.str() << std::endl << std::endl;
    }
   private:
    segwayrmp::SegwayRMP my_segway_rmp;
   };
Parameters
status_callbackA function pointer to the callback to handle new SegwayStatus updates.
Todo:
Make all the callbacks capable of taking class methods

Definition at line 715 of file segwayrmp.cc.

void SegwayRMP::setTimestampCallback ( GetTimeCallback  callback)

Sets the Callback Function to be called on when a timestamp is made.

This allows you to provide your own time stamp method for time stamping the segway data. You must return a SegwayTimeStruct, but you can return an empty time struct and manually store your time stamp and use your timestamp when processing the segway status callback.

The provided function must follow this prototype:

   SegwayTime yourTimestampCallback()

Here is an example:

   SegwayTime yourTimestampCallback() {
       SegwayTime st;
       timespec start;
       clock_gettime(CLOCK_REALTIME, &start);
       st.sec  = start.tv_sec;
       st.nsec = start.tv_nsec;
       return st;
   }

And the resulting call to make it the callback:

   segwayrmp::SegwayRMP my_segway_rmp;
   my_segway_rmp.setTimestampCallback(yourTimestampCallback);

Alternatively you can use a class method as a callback using boost::bind:

   #include <boost/bind.hpp>
   #include <ctime>
   #include "segwayrmp.h"
   class MySegwayWrapper
   {
   public:
    MySegwayWrapper () {
      my_segway_rmp.setTimestampCallback(
        boost::bind(&MySegwayWrapper::handleTimestamp, this, _1));
    }
    SegwayTime handleTimestamp() {
       SegwayTime st;
       timespec start;
       clock_gettime(CLOCK_REALTIME, &start);
       st.sec  = start.tv_sec;
       st.nsec = start.tv_nsec;
       return st;
    }
   private:
    segwayrmp::SegwayRMP my_segway_rmp;
   };
Parameters
callbackA function pointer to the callback to handle Timestamp creation.

Definition at line 736 of file segwayrmp.cc.

void SegwayRMP::shutdown ( )

Sends a shutdown command to the RMP that immediately shuts it down.

Definition at line 348 of file segwayrmp.cc.

void SegwayRMP::StartReadingContinuously_ ( )
private

Definition at line 778 of file segwayrmp.cc.

void SegwayRMP::StopReadingContinuously_ ( )
private

Definition at line 786 of file segwayrmp.cc.

Member Data Documentation

boost::thread segwayrmp::SegwayRMP::callback_execution_thread_
private

Definition at line 768 of file segwayrmp.h.

bool segwayrmp::SegwayRMP::connected_
private

Definition at line 743 of file segwayrmp.h.

bool segwayrmp::SegwayRMP::continuously_reading_
private

Definition at line 766 of file segwayrmp.h.

LogMsgCallback segwayrmp::SegwayRMP::debug_
private

Definition at line 757 of file segwayrmp.h.

double segwayrmp::SegwayRMP::dps_to_counts_
private

Definition at line 748 of file segwayrmp.h.

LogMsgCallback segwayrmp::SegwayRMP::error_
private

Definition at line 757 of file segwayrmp.h.

GetTimeCallback segwayrmp::SegwayRMP::get_time_
private

Definition at line 756 of file segwayrmp.h.

ExceptionCallback segwayrmp::SegwayRMP::handle_exception_
private

Definition at line 758 of file segwayrmp.h.

LogMsgCallback segwayrmp::SegwayRMP::info_
private

Definition at line 757 of file segwayrmp.h.

InterfaceType segwayrmp::SegwayRMP::interface_type_
private

Definition at line 739 of file segwayrmp.h.

double segwayrmp::SegwayRMP::meters_to_counts_
private

Definition at line 750 of file segwayrmp.h.

double segwayrmp::SegwayRMP::mps_to_counts_
private

Definition at line 749 of file segwayrmp.h.

boost::thread segwayrmp::SegwayRMP::read_thread_
private

Definition at line 767 of file segwayrmp.h.

double segwayrmp::SegwayRMP::rev_to_counts_
private

Definition at line 751 of file segwayrmp.h.

RMPIO* segwayrmp::SegwayRMP::rmp_io_
private

Definition at line 736 of file segwayrmp.h.

SegwayRMPType segwayrmp::SegwayRMP::segway_rmp_type_
private

Definition at line 740 of file segwayrmp.h.

SegwayStatus::Ptr segwayrmp::SegwayRMP::segway_status_
private

Definition at line 744 of file segwayrmp.h.

FiniteConcurrentSharedQueue<SegwayStatus> segwayrmp::SegwayRMP::ss_queue_
private

Definition at line 759 of file segwayrmp.h.

SegwayStatusCallback segwayrmp::SegwayRMP::status_callback_
private

Definition at line 755 of file segwayrmp.h.

double segwayrmp::SegwayRMP::torque_to_counts_
private

Definition at line 752 of file segwayrmp.h.


The documentation for this class was generated from the following files:


libsegwayrmp
Author(s): William Woodall
autogenerated on Mon Jun 10 2019 13:46:50