gearbox.cpp
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 ***************************************************************************************************/
32 #include "gearbox.h"
33 
34 namespace atlascar_base
35 {
36 
37 
38 Gearbox::Gearbox(const ros::NodeHandle& nh)
39 :nh_(nh),
40 // server_ip_gearbox(ip_),
41 // server_port_gearbox(port_),
42 // ip_("192.168.1.123"),
43 ip_("10.0.0.213"),
44 port_(120),
45 status_freq_("Gearbox",updater_,diagnostic_updater::FrequencyStatusParam(&status_max_frequency_,&status_min_frequency_, 0.1, 10)),
46 status_max_frequency_(8.0),
47 status_min_frequency_(12.0)
48 {
49  comm_=NULL;
50 }
51 
53 {
54 }
55 
57 {
58  safety_command_.reset(new atlascar_base::GearboxCommand);
59 
60  //Set the safety message default values, this messages will never be removed from the list
61  safety_command_->lifetime=INFINITY;
62  safety_command_->priority=0;
63  safety_command_->gear=0;
64 
65  //Push the safety message into the queue
67 
68  //Set diagnostics
69  updater_.setHardwareID("gearbox");
70  updater_.add("Gearbox",this,&atlascar_base::Gearbox::diagnostics);
71 }
72 
74 {
75  command_sub_ = nh_.subscribe("command", 1, &Gearbox::commandCallback, this);
76  status_pub_ = nh_.advertise<atlascar_base::GearboxStatus>("status", 1);
77 }
78 
80 {
81  // String to contain the received message:
82  string received_message;
83  // String to contain the message to send:
84  char send[1024];
85 
86  ros::Rate r(12);//Hz
87 
88  do
89  {
90  updater_.update();
91 
92  //Get top layer message, the command message that has the most priority and is still valid
93  command_=command_queue_.top_msg();
94 
95  //Check the status of the connection and reconnect if needed
97 
98  //Commandar e ler o estado da caixa
99  //a variabel de controlo é command_
100  //a variabvle de estado é status_
101 
102  if (command_->gear<7 && connection_status_==ONLINE)
103  {
104 // cout<<"Setting gear: "<<command_->gear<<endl;
105  sprintf(send,"sg %d",command_->gear);
106  comm_->Send(send,strlen(send)+1);
107  comm_->perr("Failed to send");
108 
109  // If a message is received:
110  if(receiveMessage(received_message)==0)
111  interpreterMessage(received_message);
112  }
113 
114 // cout<<"Get current state"<<endl;
115  sprintf(send,"gg");
116  comm_->Send(send,strlen(send)+1);
117  comm_->perr("Failed to send");
118 
119  if(receiveMessage(received_message)==0)
120  interpreterMessage(received_message);
121 
122 
123  //Publish the status message
124  status_.header.stamp = ros::Time::now();
125  status_.header.frame_id = "";
126  status_pub_.publish(status_);
127  status_freq_.tick();
128 
129  //Spin ros and sleep the desired amount
130  ros::spinOnce();
131  r.sleep();
132  }while(ros::ok());
133 }
134 
135 void Gearbox::commandCallback(const atlascar_base::GearboxCommandPtr& command)
136 {
137  command_queue_.push_msg(command);
138 }
139 
141 {
142  if(connection_status_==ONLINE)//Connection is active nothing to do
143  return 0;
144 
145  if(comm_)//if the comm already exists
146  {
147  //Disconnect Ethernet
148  comm_->Disconnect();
149  //Delete Ethernet object
150  delete comm_;
151  }
152 
153  comm_=new tcp_client(ip_.c_str(),port_);
154 
155  errno=0;
156 
157  struct timeval timeout = {1,0};//set 1 sec timeout for read and write
158  setsockopt(comm_->GetSocket(),SOL_SOCKET,SO_SNDTIMEO,&timeout, sizeof(timeout));
159  setsockopt(comm_->GetSocket(),SOL_SOCKET,SO_RCVTIMEO,&timeout, sizeof(timeout));
160 
161  comm_->Connect();
162  if(comm_->err<0)
163  {
164  std::cout<<"Cannot connect to gearbox: "<<comm_->err_msg<<" "<<strerror(errno)<<std::endl;
165  comm_->Disconnect();
167  return -1;
168  }
169 
170  std::cout<<"reconnection sucessfull."<<std::endl;
171 
173 
174  return 0;
175 }
176 
177 int Gearbox::interpreterMessage(string& message)
178 {
179  char opcode[100];
180  char code;
181  int current_gear;
182  int next_gear;
183 
184 // cout<<"Message: >"<<message.c_str()<<"<"<<endl;
185 
186  sscanf(message.c_str(),"%*c %s",opcode);
187 
188  if (opcode[0]=='u')
189  {
190  status_.status="command unknown";
191  return -1;
192  }
193 
194  sscanf(message.c_str(),"%*c %*s %c",&code);
195  switch (code)
196  {
197  case 'i':
198  status_.status="command invalid";
199  break;
200  case 'm':
201  status_.status="manual mode";
202  break;
203  case 'c':
204  sscanf(message.c_str(),"%*c %*s %*c %d %*c %d",&current_gear,&next_gear);
205  status_.gear=current_gear;
206 
207  status_.status="changing to "+boost::lexical_cast<std::string>(next_gear);
208 // cout<<"GEARBOX: "<<status_.status<<endl;
209 
210  break;
211  case 'a':
212  sscanf(message.c_str(),"%*c %*s %*c %d",&current_gear);
213  status_.gear=current_gear;
214  status_.status="ok";
215 
216 // cout<<"GEARBOX: "<<status_.status<<" current gear: "<<current_gear<<endl;
217 
218  break;
219  default:
220  status_.status="unrecognised status";
221  break;
222  }
223 
224  return 0;
225 }
226 
227 
228 
229 
230 
231 int Gearbox::receiveMessage(string& message)
232 {
233  char rec_buf[1024];
234  char recv_msg[1024];
235  memset(recv_msg,0,sizeof(recv_msg));
236 
237  while(rec_buf[0]!=2)
238  {
239  if(comm_->Receive(rec_buf,1)!=0)
240  {
241  comm_->Disconnect();
242  comm_->perr("Cannot read");
243  }
244 
245  if(comm_->err<0)
246  return -1;
247  }
248 
249  int i=0;
250  while(rec_buf[0]!=3)
251  {
252  if(comm_->Receive(rec_buf,1)!=0)
253  {
254  comm_->Disconnect();
255  comm_->perr("Cannot read");
256  }
257 
258  if(comm_->err<0)
259  return -1;
260  recv_msg[i++]=rec_buf[0];
261  }
262 
263  recv_msg[i-1]='\0';
264  message=recv_msg;
265 
266  return 0;
267 }
268 
269 }
ros::Subscriber command_sub_
Ros command subscriber.
Definition: gearbox.h:151
atlascar_base::GearboxStatus status_
Status message.
Definition: gearbox.h:167
Gearbox class declaration.
~Gearbox()
Class destructor.
Definition: gearbox.cpp:52
Gearbox(const ros::NodeHandle &nh)
Class constructor.
Definition: gearbox.cpp:38
diagnostic_updater::HeaderlessTopicDiagnostic status_freq_
Definition: gearbox.h:175
int maintainConnection()
Keep connection alive.
Definition: gearbox.cpp:140
tcp_client * comm_
TCP client communication class pointer.
Definition: gearbox.h:155
int interpreterMessage(string &message)
Definition: gearbox.cpp:177
TopicQueuePriority< atlascar_base::GearboxCommandPtr > command_queue_
Command queue holding class.
Definition: gearbox.h:157
atlascar_base::GearboxCommandPtr safety_command_
Safety command message pointer.
Definition: gearbox.h:165
void loop()
Start main control loop.
Definition: gearbox.cpp:79
ros::Publisher status_pub_
Ros status publisher.
Definition: gearbox.h:153
diagnostic_updater::Updater updater_
Definition: gearbox.h:174
ros::NodeHandle nh_
Ros node handler.
Definition: gearbox.h:149
atlascar_base::GearboxCommandPtr command_
Command message pointer.
Definition: gearbox.h:163
void commandCallback(const atlascar_base::GearboxCommandPtr &command)
Command message handler.
Definition: gearbox.cpp:135
int receiveMessage(string &message)
Definition: gearbox.cpp:231
std::string ip_
Definition: gearbox.h:169
void setupMessaging()
Start ros message subscribing and advertising.
Definition: gearbox.cpp:73
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: gearbox.h:114
int connection_status_
Current connection status.
Definition: gearbox.h:159
void init()
Initialize the class.
Definition: gearbox.cpp:56


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