atlascar_base::Throttle Class Reference

Throttle monitor and control class. More...

#include <throttle.h>

List of all members.

Public Member Functions

Mandatory common functions

These functions are mandatory to all low level classes in the atlacar_base namespace. All these must operate in a similar fashion across class. The constructor must only initialize variable values, all major initializations must be done in the init() function, setupMessaging() subscribes and advertises command messages and status (in that order). The loop() function will block the program in a constant loop relaying information to the hardware.

The loop() function can operate in two fashions: setting a spin rate and calling ros::spinOnce() or calling directly ros::spin() if the command callback has been setup properly. In this class (Throttle) it works by calling the ros::spinOnce() at a predefined rate.

Warning:
These functions are MANDATORY
void init ()
 Initialize the class.
void loop ()
 Start main control loop.
void setupMessaging ()
 Start ros message subscribing and advertising.
 Throttle (const ros::NodeHandle &nh, std::string ip, std::string port)
 Class constructor.
 ~Throttle ()
 Class destructor.

Private Types

enum  { MANUAL = 0, AUTO = 1 }

Private Member Functions

void commandCallback (const atlascar_base::ThrottleCommandPtr &command)
 This function handles newly received commands.
void connectHandler (void)
 This function will be called (asynchronously) on a successful connection.
void diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 Diagnostics function handler.
void newData (string data)
 This function will be called (asynchronously) upon arrival of new data.

Private Attributes

AsyncClient comm_
 Asynchronous tcp/ip communication object.
atlascar_base::ThrottleCommandPtr command_
 Command message pointer.
TopicQueuePriority
< atlascar_base::ThrottleCommandPtr > 
command_queue_
 Command queue holding class.
ros::Subscriber command_sub_
 Ros command subscriber.
int current_mode_
 Current working mode.
boost::asio::io_service io_service_
 Input/Output communication service.
ros::NodeHandle nh_
 Ros node handler.
atlascar_base::ThrottleCommandPtr safety_command_
 Safety command message pointer.
std::string server_ip_
 Throttle server ip.
std::string server_port_
 Throttle server port.
atlascar_base::ThrottleStatus status_
 Status message.
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
 Frequency diagnostics tool.
double status_max_frequency_
 Maximum admissible frequency.
double status_min_frequency_
 Minimum admissible frequency.
ros::Publisher status_pub_
 Ros status publisher.
diagnostic_updater::Updater updater_
 Diagnostics class.

Detailed Description

Throttle monitor and control class.

This class handles all communication with the atlascar throttle controller. This system controls the vehicle throttle.

Definition at line 66 of file throttle.h.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
MANUAL 
AUTO 

Definition at line 226 of file throttle.h.


Constructor & Destructor Documentation

atlascar_base::Throttle::Throttle ( const ros::NodeHandle &  nh,
std::string  ip,
std::string  port 
) [inline]

Class constructor.

Mandatory. Should only be used for variable initialization.

The constructor is used to set the server ip and port, initializing the communications service and object and the ros node handler. It also initializes the frequency diagnostics tool with the allowed maximum and minimum frequency.

Definition at line 91 of file throttle.h.

atlascar_base::Throttle::~Throttle (  )  [inline]

Class destructor.

Definition at line 104 of file throttle.h.


Member Function Documentation

void atlascar_base::Throttle::commandCallback ( const atlascar_base::ThrottleCommandPtr &  command  )  [inline, private]

This function handles newly received commands.

Parameters:
command received command message This function pushes the message to the command queue.

Definition at line 278 of file throttle.h.

void atlascar_base::Throttle::connectHandler ( void   )  [inline, private]

This function will be called (asynchronously) on a successful connection.

This function sends the start command to the Arduino, this order will signal the Arduino to start sending data.

Definition at line 260 of file throttle.h.

void atlascar_base::Throttle::diagnostics ( diagnostic_updater::DiagnosticStatusWrapper &  stat  )  [inline, private]

Diagnostics function handler.

Parameters:
stat diagnostics information storage

This function preforms diagnostics on the communication with the Arduino and reports back to the diagnostics tool.

Definition at line 234 of file throttle.h.

void atlascar_base::Throttle::init (  )  [inline]

Initialize the class.

Mandatory. To specific initialization tasks, anything that cannot be preformed in the constructor should be done here.

This function initializes the diagnostics tool and sets the communication handlers for received data and connection established.

Definition at line 115 of file throttle.h.

void atlascar_base::Throttle::loop (  )  [inline]

Start main control loop.

Mandatory. Do the main loop of the program, call ros spin or spinOnce as needed, should only quit on ros exit command.

This function launches the io service in a separate thread and then starts to do spin ros. The while cycle is used to update the diagnostics tool and send commands to the controller. Once the ros::ok() returns false the io service is stopped the thread closed and the loop quits.

Definition at line 161 of file throttle.h.

void atlascar_base::Throttle::newData ( string  data  )  [inline, private]

This function will be called (asynchronously) upon arrival of new data.

Parameters:
data incoming data in std::string format

This function handles new data coming from the Arduino. The new data is interpreted and a status message is published. This function uses boost::qi parser to interpret the message, this parser is quite complicated but very expansible, see the documentation for a tutorial on its use (it's pretty funny).

Definition at line 290 of file throttle.h.

void atlascar_base::Throttle::setupMessaging (  )  [inline]

Start ros message subscribing and advertising.

Mandatory. Subscribe command messages and advertise status messages.

This function advertises the status messages and subscribes command messages.

Definition at line 146 of file throttle.h.


Member Data Documentation

AsyncClient atlascar_base::Throttle::comm_ [private]

Asynchronous tcp/ip communication object.

Definition at line 347 of file throttle.h.

atlascar_base::ThrottleCommandPtr atlascar_base::Throttle::command_ [private]

Command message pointer.

Definition at line 322 of file throttle.h.

TopicQueuePriority<atlascar_base::ThrottleCommandPtr> atlascar_base::Throttle::command_queue_ [private]

Command queue holding class.

Definition at line 320 of file throttle.h.

ros::Subscriber atlascar_base::Throttle::command_sub_ [private]

Ros command subscriber.

Definition at line 316 of file throttle.h.

Current working mode.

Definition at line 328 of file throttle.h.

boost::asio::io_service atlascar_base::Throttle::io_service_ [private]

Input/Output communication service.

Definition at line 345 of file throttle.h.

ros::NodeHandle atlascar_base::Throttle::nh_ [private]

Ros node handler.

Definition at line 314 of file throttle.h.

atlascar_base::ThrottleCommandPtr atlascar_base::Throttle::safety_command_ [private]

Safety command message pointer.

Definition at line 324 of file throttle.h.

std::string atlascar_base::Throttle::server_ip_ [private]

Throttle server ip.

Definition at line 331 of file throttle.h.

Throttle server port.

Definition at line 333 of file throttle.h.

atlascar_base::ThrottleStatus atlascar_base::Throttle::status_ [private]

Status message.

Definition at line 326 of file throttle.h.

diagnostic_updater::HeaderlessTopicDiagnostic atlascar_base::Throttle::status_freq_ [private]

Frequency diagnostics tool.

Definition at line 338 of file throttle.h.

Maximum admissible frequency.

Definition at line 340 of file throttle.h.

Minimum admissible frequency.

Definition at line 342 of file throttle.h.

ros::Publisher atlascar_base::Throttle::status_pub_ [private]

Ros status publisher.

Definition at line 318 of file throttle.h.

diagnostic_updater::Updater atlascar_base::Throttle::updater_ [private]

Diagnostics class.

Definition at line 336 of file throttle.h.


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


atlascar_base
Author(s): Jorge Almeida, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Wed Jul 23 04:34:35 2014