plc.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 #ifndef _PLC_H_
28 #define _PLC_H_
29 
35 #include <ros/ros.h>
36 #include <iostream>
37 
38 // #include <tcp_client/class_tcp.h>
39 #include <tcp_client/AsyncClient.h>
40 
41 #include <atlascar_base/PlcStatus.h>
42 #include <atlascar_base/PlcCommand.h>
43 
44 #include <topic_priority/topic_priority.h>
45 
46 #include <boost/format.hpp>
47 #include <boost/thread/thread.hpp>
48 #include <boost/spirit/include/qi.hpp>
49 #include <boost/spirit/include/phoenix_core.hpp>
50 #include <boost/spirit/include/phoenix_operator.hpp>
51 
52 
53 #include <diagnostic_updater/diagnostic_updater.h>
54 #include <diagnostic_updater/publisher.h>
55 
56 using namespace std;
57 
58 namespace atlascar_base
59 {
60 
62 {
63  public:
64 
67 
70 
78  double remap(double value)
79  {
80  assert(minimum_value_!=maximum_value_);
81  assert(minimum_required_!=maximum_required_);
82 
83  if(minimum_value_>maximum_value_)
84  return remapInverted(value);
85 
86  if(value<minimum_value_)
87  value=minimum_value_;
88 
89  if(value>maximum_value_)
90  value=maximum_value_;
91 
92  double m = (maximum_required_-minimum_required_)/(maximum_value_-minimum_value_);
93  double b = maximum_required_ - m*maximum_value_;
94 
95  return value*m+b;
96  }
97 
98 
99  double remapInverted(double value)
100  {
101  assert(minimum_value_!=maximum_value_);
102  assert(minimum_required_!=maximum_required_);
103 
104  if(value>minimum_value_)
105  value=minimum_value_;
106 
107  if(value<maximum_value_)
108  value=maximum_value_;
109 
110  double m = (maximum_required_-minimum_required_)/(maximum_value_-minimum_value_);
111  double b = maximum_required_ - m*maximum_value_;
112 
113  return value*m+b;
114  }
115 
116  private:
117 
118 };
119 
127 class Plc
128 {
129  public:
150  Plc(const ros::NodeHandle& nh,std::string ip, std::string port);
151 
157  ~Plc();
158 
164  void init();
165 
171  void setupMessaging();
172 
180  void loop();
181 
186  private:
187 
194  void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
195  {
196  if(!comm_.isConnected())
197  {
198  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
199  stat.add("Status",comm_.error_.message());
200  stat.add("Trying to connect to",server_ip_);
201  stat.add("Port number",server_port_);
202  }else
203  {
204  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
205  stat.add("Connected with",server_ip_);
206  stat.add("Port number",server_port_);
207 
208  boost::format fmt("%.2f");
209  fmt % (ros::Time::now()-status_.header.stamp).toSec();
210 
211  stat.add("Last message sent", fmt.str()+" seconds ago" );
212  }
213  }
214 
221  void newData(string data);
222 
229  int sendCommand(void);
230 
237  int sendMessage(char*message_string);
238 
245  void commandCallback(const atlascar_base::PlcCommandPtr& command);
246 
253  SimpleCalibration steering_wheel_calibration_;
257 
262 
264  std::string server_ip_;
266  std::string server_port_;
267 
269  ros::NodeHandle nh_;
271  ros::Subscriber command_sub_;
273  ros::Publisher status_pub_;
275  TopicQueuePriority<atlascar_base::PlcCommandPtr> command_queue_;
279  bool verbose_;
281  char received_message_[1024];
283  atlascar_base::PlcCommandPtr command_;
285  atlascar_base::PlcCommandPtr safety_command_;
287  atlascar_base::PlcStatus status_;
288 
290  diagnostic_updater::Updater updater_;
292  diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
297 
299  boost::asio::io_service io_service_;
301  AsyncClient comm_;
305 };
306 
307 }
308 
309 #endif
TopicQueuePriority< atlascar_base::PlcCommandPtr > command_queue_
Command queue holding class.
Definition: plc.h:275
boost::asio::io_service io_service_
Input/Output communication service.
Definition: plc.h:299
atlascar_base::PlcStatus status_
Status message.
Definition: plc.h:287
bool verbose_
Verbose mode.
Definition: plc.h:279
diagnostic_updater::Updater updater_
Diagnostics class.
Definition: plc.h:290
Plc communication and control class.
Definition: plc.h:127
SimpleCalibration brake_calibration_
Calibration of the brake pedal.
Definition: plc.h:259
AsyncClient comm_
Asynchronous tcp/ip communication object.
Definition: plc.h:301
ros::Publisher status_pub_
Ros status publisher.
Definition: plc.h:273
std::string server_ip_
Ip of the Plc server.
Definition: plc.h:264
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Diagnostics function handler.
Definition: plc.h:194
double status_min_frequency_
Minimum admissible frequency.
Definition: plc.h:296
SimpleCalibration steering_wheel_to_plc_calibration_
Calibration of the steering wheel to the plc.
Definition: plc.h:256
double status_max_frequency_
Maximum admissible frequency.
Definition: plc.h:294
SimpleCalibration clutch_calibration_
Calibration of the clutch pedal.
Definition: plc.h:261
std::string server_port_
Port of the Plc server.
Definition: plc.h:266
atlascar_base::PlcCommandPtr command_
Command message pointer.
Definition: plc.h:283
atlascar_base::PlcCommandPtr safety_command_
Safety command message pointer.
Definition: plc.h:285
double remap(double value)
Linear mapping function.
Definition: plc.h:78
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
Frequency diagnostics tool.
Definition: plc.h:292
double remapInverted(double value)
Definition: plc.h:99
ros::NodeHandle nh_
Ros node handler.
Definition: plc.h:269
int connection_status_
Current connection status.
Definition: plc.h:277
ros::Subscriber command_sub_
Ros command subscriber.
Definition: plc.h:271


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23