Plc communication and control class. More...
#include <plc.h>
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.
| |
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 | |
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. |
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.
atlascar_base::Plc::Plc | ( | const ros::NodeHandle & | nh, | |
std::string | ip, | |||
std::string | port | |||
) |
void atlascar_base::Plc::commandCallback | ( | const atlascar_base::PlcCommandPtr & | command | ) | [private] |
void atlascar_base::Plc::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, private] |
void atlascar_base::Plc::init | ( | ) |
void atlascar_base::Plc::loop | ( | ) |
void atlascar_base::Plc::newData | ( | string | data | ) | [private] |
int atlascar_base::Plc::sendCommand | ( | void | ) | [private] |
int atlascar_base::Plc::sendMessage | ( | char * | message_string | ) | [private] |
void atlascar_base::Plc::setupMessaging | ( | ) |
AsyncClient atlascar_base::Plc::comm_ [private] |
atlascar_base::PlcCommandPtr atlascar_base::Plc::command_ [private] |
TopicQueuePriority<atlascar_base::PlcCommandPtr> atlascar_base::Plc::command_queue_ [private] |
ros::Subscriber atlascar_base::Plc::command_sub_ [private] |
int atlascar_base::Plc::connection_status_ [private] |
boost::asio::io_service atlascar_base::Plc::io_service_ [private] |
ros::NodeHandle atlascar_base::Plc::nh_ [private] |
char atlascar_base::Plc::received_message_[1024] [private] |
atlascar_base::PlcCommandPtr atlascar_base::Plc::safety_command_ [private] |
std::string atlascar_base::Plc::server_ip_ [private] |
std::string atlascar_base::Plc::server_port_ [private] |
atlascar_base::PlcStatus atlascar_base::Plc::status_ [private] |
diagnostic_updater::HeaderlessTopicDiagnostic atlascar_base::Plc::status_freq_ [private] |
double atlascar_base::Plc::status_max_frequency_ [private] |
double atlascar_base::Plc::status_min_frequency_ [private] |
ros::Publisher atlascar_base::Plc::status_pub_ [private] |
diagnostic_updater::Updater atlascar_base::Plc::updater_ [private] |
bool atlascar_base::Plc::verbose_ [private] |