odometer::Odometer Class Reference

Odometer monitor class. More...

#include <odometer.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 (Odometer) 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.
 Odometer (const ros::NodeHandle &nh, std::string ip, std::string port)
 Class constructor.
void setupMessaging ()
 Start ros message subscribing and advertising.
 ~Odometer ()
 Class destructor.

Private Member Functions

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.
boost::asio::io_service io_service_
 Input/Output communication service.
ros::NodeHandle nh_
 Ros node handler.
std::string server_ip_
 Ip of the Arduino server.
std::string server_port_
 Port of the Arduino server.
odometer::OdometerStatus 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

Odometer monitor class.

This class handles all communications with the vehicle odometer. This system obtains the real velocity of the vehicle left read wheel.

Definition at line 64 of file odometer.h.


Constructor & Destructor Documentation

odometer::Odometer::Odometer ( 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 89 of file odometer.h.

odometer::Odometer::~Odometer (  )  [inline]

Class destructor.

Definition at line 103 of file odometer.h.


Member Function Documentation

void odometer::Odometer::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 183 of file odometer.h.

void odometer::Odometer::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 232 of file odometer.h.

void odometer::Odometer::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 114 of file odometer.h.

void odometer::Odometer::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 only. Once the ros::ok() returns false the io service is stopped the thread closed and the loop quits.

Definition at line 150 of file odometer.h.

void odometer::Odometer::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 (its pretty funny).

Definition at line 201 of file odometer.h.

void odometer::Odometer::setupMessaging (  )  [inline]

Start ros message subscribing and advertising.

Mandatory. Subscribe command messages and advertise status messages.

This function only advertises the status messages.

Definition at line 135 of file odometer.h.


Member Data Documentation

AsyncClient odometer::Odometer::comm_ [private]

Asynchronous tcp/ip communication object.

Definition at line 277 of file odometer.h.

boost::asio::io_service odometer::Odometer::io_service_ [private]

Input/Output communication service.

Definition at line 275 of file odometer.h.

ros::NodeHandle odometer::Odometer::nh_ [private]

Ros node handler.

Definition at line 258 of file odometer.h.

std::string odometer::Odometer::server_ip_ [private]

Ip of the Arduino server.

Definition at line 253 of file odometer.h.

std::string odometer::Odometer::server_port_ [private]

Port of the Arduino server.

Definition at line 255 of file odometer.h.

odometer::OdometerStatus odometer::Odometer::status_ [private]

Status message.

Definition at line 264 of file odometer.h.

diagnostic_updater::HeaderlessTopicDiagnostic odometer::Odometer::status_freq_ [private]

Frequency diagnostics tool.

Definition at line 269 of file odometer.h.

Maximum admissible frequency.

Definition at line 271 of file odometer.h.

Minimum admissible frequency.

Definition at line 273 of file odometer.h.

ros::Publisher odometer::Odometer::status_pub_ [private]

Ros status publisher.

Definition at line 261 of file odometer.h.

diagnostic_updater::Updater odometer::Odometer::updater_ [private]

Diagnostics class.

Definition at line 267 of file odometer.h.


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


odometer
Author(s): Jorge Almeida
autogenerated on Wed Jul 23 04:34:44 2014