00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 #ifndef _PLC_H_
00028 #define _PLC_H_
00029 
00035 #include <ros/ros.h>
00036 #include <iostream>
00037 
00038 
00039 #include <tcp_client/AsyncClient.h>
00040 
00041 #include <atlascar_base/PlcStatus.h>
00042 #include <atlascar_base/PlcCommand.h>
00043 
00044 #include <topic_priority/topic_priority.h>
00045 
00046 #include <boost/format.hpp>
00047 #include <boost/thread/thread.hpp>
00048 #include <boost/spirit/include/qi.hpp>
00049 #include <boost/spirit/include/phoenix_core.hpp>
00050 #include <boost/spirit/include/phoenix_operator.hpp>
00051 
00052 
00053 #include <diagnostic_updater/diagnostic_updater.h>
00054 #include <diagnostic_updater/publisher.h>
00055 
00056 using namespace std;
00057 
00058 namespace atlascar_base
00059 {
00060 
00061 class SimpleCalibration 
00062 {
00063         public:
00064                 
00065                 double maximum_value_;
00066                 double minimum_value_;
00067                 
00068                 double maximum_required_;
00069                 double minimum_required_;
00070         
00078                 double remap(double value)
00079                 {
00080                         assert(minimum_value_!=maximum_value_);
00081                         assert(minimum_required_!=maximum_required_);
00082                         
00083                         if(minimum_value_>maximum_value_)
00084                                 return remapInverted(value);
00085                         
00086                         if(value<minimum_value_)
00087                                 value=minimum_value_;
00088                         
00089                         if(value>maximum_value_)
00090                                 value=maximum_value_;
00091                         
00092                         double m = (maximum_required_-minimum_required_)/(maximum_value_-minimum_value_);
00093                         double b = maximum_required_ - m*maximum_value_;
00094                         
00095                         return value*m+b;
00096                 }
00097                 
00098                 
00099                 double remapInverted(double value)
00100                 {
00101                         assert(minimum_value_!=maximum_value_);
00102                         assert(minimum_required_!=maximum_required_);
00103                         
00104                         if(value>minimum_value_)
00105                                 value=minimum_value_;
00106                         
00107                         if(value<maximum_value_)
00108                                 value=maximum_value_;
00109                         
00110                         double m = (maximum_required_-minimum_required_)/(maximum_value_-minimum_value_);
00111                         double b = maximum_required_ - m*maximum_value_;
00112                         
00113                         return value*m+b;
00114                 }
00115                 
00116         private:
00117                 
00118 };
00119         
00127 class Plc
00128 {
00129         public:
00150                 Plc(const ros::NodeHandle& nh,std::string ip, std::string port);
00151                 
00157                 ~Plc();
00158                 
00164                 void init();
00165                 
00171                 void setupMessaging();
00172                 
00180                 void loop();
00181                 
00186         private:
00187                 
00194                 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00195                 {
00196                         if(!comm_.isConnected())
00197                         {
00198                                 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No connection to hardware.");
00199                                 stat.add("Status",comm_.error_.message());
00200                                 stat.add("Trying to connect to",server_ip_);
00201                                 stat.add("Port number",server_port_);
00202                         }else
00203                         {
00204                                 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No problems.");
00205                                 stat.add("Connected with",server_ip_);
00206                                 stat.add("Port number",server_port_);
00207                                 
00208                                 boost::format fmt("%.2f");
00209                                 fmt % (ros::Time::now()-status_.header.stamp).toSec();
00210                                 
00211                                 stat.add("Last message sent", fmt.str()+" seconds ago" );
00212                         }
00213                 }
00214                 
00221                 void newData(string data);
00222                 
00229                 int sendCommand(void);
00230                 
00237                 int sendMessage(char*message_string);
00238 
00245                 void commandCallback(const atlascar_base::PlcCommandPtr& command);
00246                 
00253 
00254                 SimpleCalibration steering_wheel_calibration_;
00256                 SimpleCalibration steering_wheel_to_plc_calibration_;
00257                 
00259                 SimpleCalibration brake_calibration_;
00261                 SimpleCalibration clutch_calibration_;
00262                 
00264                 std::string server_ip_;
00266                 std::string server_port_;
00267                 
00269                 ros::NodeHandle nh_;
00271                 ros::Subscriber command_sub_;
00273                 ros::Publisher status_pub_;
00275                 TopicQueuePriority<atlascar_base::PlcCommandPtr> command_queue_;                
00277                 int connection_status_;
00279                 bool verbose_;
00281                 char received_message_[1024];
00283                 atlascar_base::PlcCommandPtr command_;
00285                 atlascar_base::PlcCommandPtr safety_command_;
00287                 atlascar_base::PlcStatus status_;
00288                 
00290                 diagnostic_updater::Updater updater_;
00292                 diagnostic_updater::HeaderlessTopicDiagnostic status_freq_;
00294                 double status_max_frequency_;
00296                 double status_min_frequency_;
00297                 
00299                 boost::asio::io_service io_service_;
00301                 AsyncClient comm_;
00305 };
00306 
00307 }
00308 
00309 #endif