Public Member Functions | Static Public Attributes

JAUS::LocalWaypointDriver Class Reference

The Local Waypoint Driver allows for the driving of platform to a target waypoint. More...

#include <localwaypointdriver.h>

Inheritance diagram for JAUS::LocalWaypointDriver:
JAUS::Management::Child JAUS::AccessControl::Child JAUS::Events::Child JAUS::Service

List of all members.

Public Member Functions

 LocalWaypointDriver ()
 Constructor.
virtual ~LocalWaypointDriver ()
 Destructor.
virtual MessageGenerateDriveCommand (const Byte status)=0
virtual MessageGenerateIdleDriveCommand (const Byte status) const =0
virtual bool IsWaypointAchieved (const LocalPose &currentPose, const JAUS::SetLocalWaypoint &desiredWaypoint) const =0
virtual void WaypointDriverUpdateEvent (const unsigned int timeSinceLastUpdateMs)
virtual void WaypointAchieved (const JAUS::SetLocalWaypoint &waypoint)=0
virtual bool SetLocalWaypoint (const JAUS::SetLocalWaypoint *command)
 Sets the current desired destination.
virtual bool SetDesiredTravelSpeed (const JAUS::SetTravelSpeed *command)
virtual bool SetDesiredTravelSpeed (const double speed)
 Sets the current desired destination.
virtual bool SetDriverToControl (const Address &driver)
 Sets the Address of the Driver to control.
virtual JAUS::SetLocalWaypoint GetLocalWaypoint () const
 Returns the current Local Waypoint command received.
virtual LocalPose GetLocalPose () const
 Returns the current Local Pose reported by the Local Pose sensor.
virtual VelocityState GetVelocityState () const
 Returns the current Velocity State reported by the Velocity State sensor.
virtual JAUS::SetTravelSpeed GetDesiredTravelSpeed () const
 Returns the desired Travel Speed command received.
virtual Time GetLocalWaypointTime () const
virtual Time GetTravelSpeedTime () const
virtual Address GetControlledDriverID () const
virtual bool GenerateEvent (const Events::Subscription &info) const
 Generates an event for the given information.
virtual bool IsEventSupported (const Events::Type type, const double requestedPeriodicRate, const Message *queryMessage, double &confirmedPeriodicRate, std::string &errorMessage) const
 Checks if the event is supported by the Service.
virtual bool IsDiscoverable () const
virtual void Receive (const Message *message)
 Processes message received by the Service. If not supported, then message is passed to inheriting services depending on what type of control has been established for the component.
virtual MessageCreateMessage (const UShort messageCode) const
 Attempts to create the message desired. Only message supported by this Service can be created by this Service.
virtual void PrintStatus () const
 Prints the status of the Local Waypoint Driver.
virtual bool Resume ()
 Method called when transitioning to a resume state. Confirms subscription to Sensors, and control of Driver.
virtual bool Reset ()
 // Method called to transition due to reset. Release Control of Driver, clear all data.
virtual bool Standby ()
 Method called when transitioning to a standby state. Release Control of the Driver and remove subscriptions if any.
virtual bool SetEmergency ()
 Method called when transitioning to an emergency state. Try to send a Idle command to the controlled Driver. Afterwards, Release control of the Driver and remove subscriptions if any.
virtual bool ClearEmergency ()
 Method called when leaving the emergency state, try to resume the the Waypoint if any.
virtual bool ReleaseControl ()
 Method called when control is released. Does not stop operatoin of driver.

Static Public Attributes

static const std::string Name = "urn:jaus:jss:mobility:LocalWaypointDriver"
 String name of the Service.

Detailed Description

The Local Waypoint Driver allows for the driving of platform to a target waypoint.

single target waypoint, desired travel speed, current platform pose and current velocity state. A single waypoint is provided via the Set Local Waypoint message. The waypoint remains unchanged until a new Set Local Waypoint message is received. A waypoint consists of the desired position and orientation of the platform. The second input consists of the desired travel speed. The travel speed remains unchanged unless a new Set Travel Speed Message is received. The travel speed may then be changed at any time during waypoint navigation. The travel speed is reset to zero for all transitions from the Ready State.

This implmentation of this service requires at a minimum a Local Pose and Velocity State sensor service on the same component that this service belongs to. The sensor services can be synchronizing versions of the services also (see example_synchronize.cpp for how to do this).

Definition at line 82 of file localwaypointdriver.h.


Constructor & Destructor Documentation

LocalWaypointDriver::LocalWaypointDriver (  )

Constructor.

Definition at line 54 of file localwaypointdriver.cpp.

LocalWaypointDriver::~LocalWaypointDriver (  ) [virtual]

Destructor.

Definition at line 69 of file localwaypointdriver.cpp.


Member Function Documentation

bool LocalWaypointDriver::ClearEmergency (  ) [virtual]

Method called when leaving the emergency state, try to resume the the Waypoint if any.

Reimplemented from JAUS::Management::Child.

Definition at line 520 of file localwaypointdriver.cpp.

Message * LocalWaypointDriver::CreateMessage ( const UShort  messageCode ) const [virtual]

Attempts to create the message desired. Only message supported by this Service can be created by this Service.

Parameters:
[in]messageCodeMessage to create.
Returns:
Pointer to newly allocated Message data, NULL if message is not supported by the Service.

Implements JAUS::Service.

Definition at line 391 of file localwaypointdriver.cpp.

virtual Message* JAUS::LocalWaypointDriver::GenerateDriveCommand ( const Byte  status ) [pure virtual]
bool LocalWaypointDriver::GenerateEvent ( const Events::Subscription info ) const [virtual]

Generates an event for the given information.

Parameters:
[in]infoThe event information (ID, Sequence #, etc.) for generation.
Returns:
True if event generated, otherwise false.

Implements JAUS::Events::Child.

Definition at line 231 of file localwaypointdriver.cpp.

virtual Message* JAUS::LocalWaypointDriver::GenerateIdleDriveCommand ( const Byte  status ) const [pure virtual]
Address LocalWaypointDriver::GetControlledDriverID (  ) const [virtual]
Returns:
The address of the Driver being controlled.

Definition at line 215 of file localwaypointdriver.cpp.

SetTravelSpeed LocalWaypointDriver::GetDesiredTravelSpeed (  ) const [virtual]

Returns the desired Travel Speed command received.

Returns:
The desired Travel Speed as a SetTravelSpeed message.

Definition at line 177 of file localwaypointdriver.cpp.

LocalPose LocalWaypointDriver::GetLocalPose (  ) const [virtual]

Returns the current Local Pose reported by the Local Pose sensor.

Returns:
The current Local Pose as a ReportLocalPose message.

Definition at line 148 of file localwaypointdriver.cpp.

SetLocalWaypoint LocalWaypointDriver::GetLocalWaypoint (  ) const [virtual]

Returns the current Local Waypoint command received.

Returns:
The current Local Waypoint as a SetLocalWaypoint message.

Definition at line 134 of file localwaypointdriver.cpp.

Time LocalWaypointDriver::GetLocalWaypointTime (  ) const [virtual]
Returns:
The time (UTC seconds) that a Set Local Waypoint command was received.

Definition at line 190 of file localwaypointdriver.cpp.

Time LocalWaypointDriver::GetTravelSpeedTime (  ) const [virtual]
Returns:
The time (UTC seconds) that a Set Travel Speed command was received.

Definition at line 203 of file localwaypointdriver.cpp.

VelocityState LocalWaypointDriver::GetVelocityState (  ) const [virtual]

Returns the current Velocity State reported by the Velocity State sensor.

Returns:
The current Velocity State as a ReportVelocityState message.

Definition at line 163 of file localwaypointdriver.cpp.

virtual bool JAUS::LocalWaypointDriver::IsDiscoverable (  ) const [inline, virtual]

Implements JAUS::Service.

Definition at line 130 of file localwaypointdriver.h.

bool LocalWaypointDriver::IsEventSupported ( const Events::Type  type,
const double  requestedPeriodicRate,
const Message queryMessage,
double &  confirmedPeriodicRate,
std::string &  errorMessage 
) const [virtual]

Checks if the event is supported by the Service.

Parameters:
[in]typeThe event type (Periodic/EveryChange).
[in]requestedPeriodicRateIf type == Periodic, then this is the desired update rate.
[in]queryMessageThe query message associated with the event.
[out]confirmedPeriodicRateThis is the confirmed periodic rate supported by the Service.
[out]errorMessageIf not supported, this is an optional error message.
Returns:
True if event supported, otherwise false.

Implements JAUS::Events::Child.

Definition at line 285 of file localwaypointdriver.cpp.

virtual bool JAUS::LocalWaypointDriver::IsWaypointAchieved ( const LocalPose currentPose,
const JAUS::SetLocalWaypoint desiredWaypoint 
) const [pure virtual]
void LocalWaypointDriver::PrintStatus (  ) const [virtual]

Prints the status of the Local Waypoint Driver.

Reimplemented from JAUS::Service.

Definition at line 427 of file localwaypointdriver.cpp.

void LocalWaypointDriver::Receive ( const Message message ) [virtual]

Processes message received by the Service. If not supported, then message is passed to inheriting services depending on what type of control has been established for the component.

This Service supports LocalWaypointDriver related messages only.

Parameters:
[in]messageMessage data to process.

Reimplemented from JAUS::Service.

Definition at line 318 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::ReleaseControl (  ) [virtual]

Method called when control is released. Does not stop operatoin of driver.

Reimplemented from JAUS::Management::Child.

Definition at line 532 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::Reset (  ) [virtual]

// Method called to transition due to reset. Release Control of Driver, clear all data.

Implements JAUS::Management::Child.

Definition at line 464 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::Resume (  ) [virtual]

Method called when transitioning to a resume state. Confirms subscription to Sensors, and control of Driver.

Implements JAUS::Management::Child.

Definition at line 452 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::SetDesiredTravelSpeed ( const double  speed ) [virtual]

Sets the current desired destination.

Parameters:
[in]speedThe desired speed of the Platform.

Definition at line 96 of file localwaypointdriver.cpp.

virtual bool JAUS::LocalWaypointDriver::SetDesiredTravelSpeed ( const JAUS::SetTravelSpeed command ) [inline, virtual]

Definition at line 102 of file localwaypointdriver.h.

bool LocalWaypointDriver::SetDriverToControl ( const Address driver ) [virtual]

Sets the Address of the Driver to control.

Returns:
False if a problem was found with the change in driver.

Definition at line 113 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::SetEmergency (  ) [virtual]

Method called when transitioning to an emergency state. Try to send a Idle command to the controlled Driver. Afterwards, Release control of the Driver and remove subscriptions if any.

Reimplemented from JAUS::Management::Child.

Definition at line 499 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::SetLocalWaypoint ( const JAUS::SetLocalWaypoint command ) [virtual]

Sets the current desired destination.

Definition at line 79 of file localwaypointdriver.cpp.

bool LocalWaypointDriver::Standby (  ) [virtual]

Method called when transitioning to a standby state. Release Control of the Driver and remove subscriptions if any.

Implements JAUS::Management::Child.

Definition at line 486 of file localwaypointdriver.cpp.

virtual void JAUS::LocalWaypointDriver::WaypointAchieved ( const JAUS::SetLocalWaypoint waypoint ) [pure virtual]
virtual void JAUS::LocalWaypointDriver::WaypointDriverUpdateEvent ( const unsigned int  timeSinceLastUpdateMs ) [inline, virtual]

Definition at line 96 of file localwaypointdriver.h.


Member Data Documentation

const std::string LocalWaypointDriver::Name = "urn:jaus:jss:mobility:LocalWaypointDriver" [static]

String name of the Service.

Definition at line 85 of file localwaypointdriver.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines