atlascar_base::Plc Class Reference

Plc communication and control class. More...

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

Private Member Functions

void commandCallback (const atlascar_base::PlcCommandPtr &command)
 Command message handler.
void diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 Diagnostics function handler.
void newData (string data)
 This function will be called (asynchronously) upon arrival of new data.
int sendCommand (void)
 Send a global command down to the plc.
int sendMessage (char *message_string)
 Send a message.

Private Attributes

Class variables

The class variables can be both public or private. They should preferably be private whenever possible.

SimpleCalibration brake_calibration_
 Calibration of the brake pedal.
SimpleCalibration clutch_calibration_
 Calibration of the clutch pedal.
AsyncClient comm_
 Asynchronous tcp/ip communication object.
atlascar_base::PlcCommandPtr command_
 Command message pointer.
TopicQueuePriority
< atlascar_base::PlcCommandPtr > 
command_queue_
 Command queue holding class.
ros::Subscriber command_sub_
 Ros command subscriber.
int connection_status_
 Current connection status.
boost::asio::io_service io_service_
 Input/Output communication service.
ros::NodeHandle nh_
 Ros node handler.
char received_message_ [1024]
 Message received.
atlascar_base::PlcCommandPtr safety_command_
 Safety command message pointer.
std::string server_ip_
 Ip of the Plc server.
std::string server_port_
 Port of the Plc server.
atlascar_base::PlcStatus 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.
SimpleCalibration steering_wheel_calibration_
 Calibration of the steering wheel from the plc.
SimpleCalibration steering_wheel_to_plc_calibration_
 Calibration of the steering wheel to the plc.
diagnostic_updater::Updater updater_
 Diagnostics class.
bool verbose_
 Verbose mode.

Detailed Description

Plc communication and control class.

This class implements the Ethernet and Plc communication protocol in order to establish a communication with it. The communication is maintained and a status message is continuously published.

Definition at line 127 of file plc.h.


Constructor & Destructor Documentation

atlascar_base::Plc::Plc ( const ros::NodeHandle &  nh,
std::string  ip,
std::string  port 
)

Class constructor.

Initialize variables, do not call any function

Definition at line 35 of file plc.cpp.

atlascar_base::Plc::~Plc (  ) 

Class destructor.

Do nothing.

Definition at line 48 of file plc.cpp.


Member Function Documentation

void atlascar_base::Plc::commandCallback ( const atlascar_base::PlcCommandPtr &  command  )  [private]

Command message handler.

Receive command messages and put them in the queue.

Parameters:
command received command message

Definition at line 278 of file plc.cpp.

void atlascar_base::Plc::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 194 of file plc.h.

void atlascar_base::Plc::init (  ) 

Initialize the class.

Add the safety message to the command queue.

Definition at line 51 of file plc.cpp.

void atlascar_base::Plc::loop (  ) 

Start main control loop.

Loop the module sending command messages to the plc, this function will only exit of the ros exit command. It currently loops at about 15Hz which is the plc maximum communication speed.

Definition at line 104 of file plc.cpp.

void atlascar_base::Plc::newData ( string  data  )  [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.

Definition at line 139 of file plc.cpp.

int atlascar_base::Plc::sendCommand ( void   )  [private]

Send a global command down to the plc.

This function prepares the command message to send, sends it and receives the plc answer.

Returns:
error code, 0 if no error <0 on error

Definition at line 187 of file plc.cpp.

int atlascar_base::Plc::sendMessage ( char *  message_string  )  [private]

Send a message.

Format the string to send, and send it.

Returns:
error code, 0 if no error <0 on error

Definition at line 264 of file plc.cpp.

void atlascar_base::Plc::setupMessaging (  ) 

Start ros message subscribing and advertising.

Subscribe command messages and advertise status messages.

Definition at line 98 of file plc.cpp.


Member Data Documentation

Calibration of the brake pedal.

Definition at line 259 of file plc.h.

Calibration of the clutch pedal.

Definition at line 261 of file plc.h.

AsyncClient atlascar_base::Plc::comm_ [private]

Asynchronous tcp/ip communication object.

Definition at line 301 of file plc.h.

atlascar_base::PlcCommandPtr atlascar_base::Plc::command_ [private]

Command message pointer.

Definition at line 283 of file plc.h.

TopicQueuePriority<atlascar_base::PlcCommandPtr> atlascar_base::Plc::command_queue_ [private]

Command queue holding class.

Definition at line 275 of file plc.h.

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

Ros command subscriber.

Definition at line 271 of file plc.h.

Current connection status.

Definition at line 277 of file plc.h.

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

Input/Output communication service.

Definition at line 299 of file plc.h.

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

Ros node handler.

Definition at line 269 of file plc.h.

Message received.

Definition at line 281 of file plc.h.

atlascar_base::PlcCommandPtr atlascar_base::Plc::safety_command_ [private]

Safety command message pointer.

Definition at line 285 of file plc.h.

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

Ip of the Plc server.

Definition at line 264 of file plc.h.

std::string atlascar_base::Plc::server_port_ [private]

Port of the Plc server.

Definition at line 266 of file plc.h.

atlascar_base::PlcStatus atlascar_base::Plc::status_ [private]

Status message.

Definition at line 287 of file plc.h.

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

Frequency diagnostics tool.

Definition at line 292 of file plc.h.

Maximum admissible frequency.

Definition at line 294 of file plc.h.

Minimum admissible frequency.

Definition at line 296 of file plc.h.

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

Ros status publisher.

Definition at line 273 of file plc.h.

Calibration of the steering wheel from the plc.

Definition at line 254 of file plc.h.

Calibration of the steering wheel to the plc.

Definition at line 256 of file plc.h.

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

Diagnostics class.

Definition at line 290 of file plc.h.

Verbose mode.

Definition at line 279 of file plc.h.


The documentation for this class was generated from the following files:
 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