p2os.cc
Go to the documentation of this file.
1 /*
2  * P2OS for ROS
3  * Copyright (C) 2009
4  * David Feil-Seifer, Brian Gerkey, Kasper Stoy,
5  * Richard Vaughan, & Andrew Howard
6  *
7  *
8  * This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program; if not, write to the Free Software
20  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
21  *
22  */
23 
24 #include <ros/ros.h>
25 #include <p2os_driver/p2os.h>
26 
27 #include <termios.h>
28 #include <fcntl.h>
29 #include <string.h>
30 
31 
32 P2OSNode::P2OSNode( ros::NodeHandle nh ) :
33  n(nh), gripper_dirty_(false),
34  batt_pub_( n.advertise<p2os_msgs::BatteryState>("battery_state",1000),
35  diagnostic_,
36  diagnostic_updater::FrequencyStatusParam( &desired_freq, &desired_freq, 0.1),
37  diagnostic_updater::TimeStampStatusParam() ),
38  ptz_(this)
39 {
45  // Use sonar
46  ros::NodeHandle n_private("~");
47  n_private.param("use_sonar", use_sonar_, false);
48 
49  // read in config options
50  // bumpstall
51  n_private.param( "bumpstall", bumpstall, -1 );
52  // pulse
53  n_private.param( "pulse", pulse, -1.0 );
54  // rot_kp
55  n_private.param( "rot_kp", rot_kp, -1 );
56  // rot_kv
57  n_private.param( "rot_kv", rot_kv, -1 );
58  // rot_ki
59  n_private.param( "rot_ki", rot_ki, -1 );
60  // trans_kp
61  n_private.param( "trans_kp", trans_kp, -1 );
62  // trans_kv
63  n_private.param( "trans_kv", trans_kv, -1 );
64  // trans_ki
65  n_private.param( "trans_ki", trans_ki, -1 );
66  // !!! port !!!
67  std::string def = DEFAULT_P2OS_PORT;
68  n_private.param( "port", psos_serial_port, def );
69  ROS_INFO( "using serial port: [%s]", psos_serial_port.c_str() );
70  n_private.param( "use_tcp", psos_use_tcp, false );
71  std::string host = DEFAULT_P2OS_TCP_REMOTE_HOST;
72  n_private.param( "tcp_remote_host", psos_tcp_host, host );
73  n_private.param( "tcp_remote_port", psos_tcp_port, DEFAULT_P2OS_TCP_REMOTE_PORT );
74  // radio
75  n_private.param( "radio", radio_modemp, 0 );
76  // joystick
77  n_private.param( "joystick", joystick, 0 );
78  // direct_wheel_vel_control
79  n_private.param( "direct_wheel_vel_control", direct_wheel_vel_control, 0 );
80  // max xpeed
81  double spd;
82  n_private.param( "max_xspeed", spd, MOTOR_DEF_MAX_SPEED);
83  motor_max_speed = (int)rint(1e3*spd);
84  // max_yawspeed
85  n_private.param( "max_yawspeed", spd, MOTOR_DEF_MAX_TURNSPEED);
86  motor_max_turnspeed = (short)rint(RTOD(spd));
87  // max_xaccel
88  n_private.param( "max_xaccel", spd, 0.0);
89  motor_max_trans_accel = (short)rint(1e3*spd);
90  // max_xdecel
91  n_private.param( "max_xdecel", spd, 0.0);
92  motor_max_trans_decel = (short)rint(1e3*spd);
93  // max_yawaccel
94  n_private.param( "max_yawaccel", spd, 0.0);
95  motor_max_rot_accel = (short)rint(RTOD(spd));
96  // max_yawdecel
97  n_private.param( "max_yawdecel", spd, 0.0);
98  motor_max_rot_decel = (short)rint(RTOD(spd));
99 
100  desired_freq = 10;
101 
102  // advertise services
103  pose_pub_ = n.advertise<nav_msgs::Odometry>("pose", 1000);
104  //advertise topics
105  mstate_pub_ = n.advertise<p2os_msgs::MotorState>("motor_state",1000);
106  grip_state_pub_ = n.advertise<p2os_msgs::GripperState>("gripper_state",1000);
107  ptz_state_pub_ = n.advertise<p2os_msgs::PTZState>("ptz_state",1000);
108  sonar_pub_ = n.advertise<p2os_msgs::SonarArray>("sonar", 1000);
109  aio_pub_ = n.advertise<p2os_msgs::AIO>("aio", 1000);
110  dio_pub_ = n.advertise<p2os_msgs::DIO>("dio", 1000);
111 
112  // subscribe to services
113  cmdvel_sub_ = n.subscribe("cmd_vel", 1, &P2OSNode::cmdvel_cb, this);
114  cmdmstate_sub_ = n.subscribe("cmd_motor_state", 1, &P2OSNode::cmdmotor_state,
115  this);
116  gripper_sub_ = n.subscribe("gripper_control", 1, &P2OSNode::gripperCallback,
117  this);
118  ptz_cmd_sub_ = n.subscribe("ptz_control", 1, &P2OSPtz::callback, &ptz_);
119 
120  veltime = ros::Time::now();
121 
122  // add diagnostic functions
123  diagnostic_.add("Motor Stall", this, &P2OSNode::check_stall );
124  diagnostic_.add("Battery Voltage", this, &P2OSNode::check_voltage );
125 
126  // initialize robot parameters (player legacy)
128 }
129 
131 {
132 }
133 
134 void P2OSNode::cmdmotor_state( const p2os_msgs::MotorStateConstPtr &msg)
135 {
136  motor_dirty = true;
137  cmdmotor_state_ = *msg;
138 }
139 
141 {
142  if( !motor_dirty ) return;
143  motor_dirty = false;
144 
145  unsigned char val = (unsigned char) cmdmotor_state_.state;
146  unsigned char command[4];
147  P2OSPacket packet;
148  command[0] = ENABLE;
149  command[1] = ARGINT;
150  command[2] = val;
151  command[3] = 0;
152  packet.Build(command,4);
153 
154  // Store the current motor state so that we can set it back
155  p2os_data.motors.state = cmdmotor_state_.state;
156  SendReceive(&packet,false);
157 }
158 
160 {
161  if( !gripper_dirty_ ) return;
162  gripper_dirty_ = false;
163 
164  // Send the gripper command
165  unsigned char grip_val = (unsigned char) gripper_state_.grip.state;
166  unsigned char grip_command[4];
167  P2OSPacket grip_packet;
168  grip_command[0] = GRIPPER;
169  grip_command[1] = ARGINT;
170  grip_command[2] = grip_val;
171  grip_command[3] = 0;
172  grip_packet.Build(grip_command,4);
173  SendReceive(&grip_packet,false);
174 
175  // Send the lift command
176  unsigned char lift_val = (unsigned char) gripper_state_.lift.state;
177  unsigned char lift_command[4];
178  P2OSPacket lift_packet;
179  lift_command[0] = GRIPPER;
180  lift_command[1] = ARGINT;
181  lift_command[2] = lift_val;
182  lift_command[3] = 0;
183  lift_packet.Build(lift_command,4);
184  SendReceive(&lift_packet,false);
185 }
186 
187 void P2OSNode::cmdvel_cb( const geometry_msgs::TwistConstPtr &msg)
188 {
189 
190  if( fabs( msg->linear.x - cmdvel_.linear.x ) > 0.01 || fabs( msg->angular.z-cmdvel_.angular.z) > 0.01 )
191  {
192  veltime = ros::Time::now();
193  ROS_DEBUG( "new speed: [%0.2f,%0.2f](%0.3f)", msg->linear.x*1e3, msg->angular.z, veltime.toSec() );
194  vel_dirty = true;
195  cmdvel_ = *msg;
196  }
197  else
198  {
199  ros::Duration veldur = ros::Time::now() - veltime;
200  if( veldur.toSec() > 2.0 && ((fabs(cmdvel_.linear.x) > 0.01) || (fabs(cmdvel_.angular.z) > 0.01)) )
201  {
202  ROS_DEBUG( "maintaining old speed: %0.3f|%0.3f", veltime.toSec(), ros::Time::now().toSec() );
203  vel_dirty = true;
204  veltime = ros::Time::now();
205  }
206  }
207 
208 }
209 
211 {
212  if( !vel_dirty ) return;
213 
214  ROS_DEBUG( "setting vel: [%0.2f,%0.2f]",cmdvel_.linear.x,cmdvel_.angular.z);
215  vel_dirty = false;
216 
217  unsigned short absSpeedDemand, absturnRateDemand;
218  unsigned char motorcommand[4];
219  P2OSPacket motorpacket;
220 
221  int vx = (int) (cmdvel_.linear.x*1e3);
222  int va = (int)rint(RTOD(cmdvel_.angular.z));
223 
224  {
225  // non-direct wheel control
226  motorcommand[0] = VEL;
227  if( vx >= 0 ) motorcommand[1] = ARGINT;
228  else motorcommand[1] = ARGNINT;
229 
230  absSpeedDemand = (unsigned short)abs(vx);
231  if( absSpeedDemand <= this->motor_max_speed )
232  {
233  motorcommand[2] = absSpeedDemand & 0x00FF;
234  motorcommand[3] = (absSpeedDemand & 0xFF00) >> 8;
235  }
236  else
237  {
238  ROS_WARN( "speed demand thresholded! (true: %u, max: %u)", absSpeedDemand, motor_max_speed );
239  motorcommand[2] = motor_max_speed & 0x00FF;
240  motorcommand[3] = (motor_max_speed & 0xFF00) >> 8;
241  }
242  motorpacket.Build(motorcommand, 4);
243  SendReceive(&motorpacket);
244 
245  motorcommand[0] = RVEL;
246  if( va >= 0 ) motorcommand[1] = ARGINT;
247  else motorcommand[1] = ARGNINT;
248 
249  absturnRateDemand = (unsigned short)abs(va);
250  if( absturnRateDemand <= motor_max_turnspeed )
251  {
252  motorcommand[2] = absturnRateDemand & 0x00FF;
253  motorcommand[3] = (absturnRateDemand & 0xFF00) >> 8;
254  }
255  else
256  {
257  ROS_WARN("Turn rate demand threshholded!");
258  motorcommand[2] = this->motor_max_turnspeed & 0x00FF;
259  motorcommand[3] = (this->motor_max_turnspeed & 0xFF00) >> 8;
260  }
261 
262  motorpacket.Build(motorcommand,4);
263  SendReceive(&motorpacket);
264  }
265 }
266 
267 void P2OSNode::gripperCallback(const p2os_msgs::GripperStateConstPtr &msg)
268 {
269  gripper_dirty_ = true;
270  gripper_state_ = *msg;
271 }
272 
274 {
275  int i;
276  int bauds[] = {B9600, B38400, B19200, B115200, B57600};
277  int numbauds = sizeof(bauds);
278  int currbaud = 0;
279  sippacket = NULL;
280  lastPulseTime = 0.0;
281 
282  struct termios term;
283  unsigned char command;
284  P2OSPacket packet, receivedpacket;
285  int flags=0;
286  bool sent_close = false;
287  enum
288  {
289  NO_SYNC,
290  AFTER_FIRST_SYNC,
291  AFTER_SECOND_SYNC,
292  READY
293  } psos_state;
294 
295  psos_state = NO_SYNC;
296 
297  char name[20], type[20], subtype[20];
298  int cnt;
299 
300 
301  // use serial port
302 
303  ROS_INFO("P2OS connection opening serial port %s...",psos_serial_port.c_str());
304 
305  if((this->psos_fd = open(this->psos_serial_port.c_str(),
306  O_RDWR | O_SYNC | O_NONBLOCK, S_IRUSR | S_IWUSR )) < 0 )
307  {
308  ROS_ERROR("P2OS::Setup():open():");
309  return(1);
310  }
311 
312  if(tcgetattr( this->psos_fd, &term ) < 0 )
313  {
314  ROS_ERROR("P2OS::Setup():tcgetattr():");
315  close(this->psos_fd);
316  this->psos_fd = -1;
317  return(1);
318  }
319 
320  cfmakeraw( &term );
321  cfsetispeed(&term, bauds[currbaud]);
322  cfsetospeed(&term, bauds[currbaud]);
323 
324  if(tcsetattr(this->psos_fd, TCSAFLUSH, &term ) < 0)
325  {
326  ROS_ERROR("P2OS::Setup():tcsetattr():");
327  close(this->psos_fd);
328  this->psos_fd = -1;
329  return(1);
330  }
331 
332  if(tcflush(this->psos_fd, TCIOFLUSH ) < 0)
333  {
334  ROS_ERROR("P2OS::Setup():tcflush():");
335  close(this->psos_fd);
336  this->psos_fd = -1;
337  return(1);
338  }
339 
340  if((flags = fcntl(this->psos_fd, F_GETFL)) < 0)
341  {
342  ROS_ERROR("P2OS::Setup():fcntl()");
343  close(this->psos_fd);
344  this->psos_fd = -1;
345  return(1);
346  }
347  // Sync:
348 
349  int num_sync_attempts = 3;
350  while(psos_state != READY)
351  {
352  switch(psos_state)
353  {
354  case NO_SYNC:
355  command = SYNC0;
356  packet.Build(&command, 1);
357  packet.Send(this->psos_fd);
358  usleep(P2OS_CYCLETIME_USEC);
359  break;
360  case AFTER_FIRST_SYNC:
361  ROS_INFO("turning off NONBLOCK mode...");
362  if(fcntl(this->psos_fd, F_SETFL, flags ^ O_NONBLOCK) < 0)
363  {
364  ROS_ERROR("P2OS::Setup():fcntl()");
365  close(this->psos_fd);
366  this->psos_fd = -1;
367  return(1);
368  }
369  command = SYNC1;
370  packet.Build(&command, 1);
371  packet.Send(this->psos_fd);
372  break;
373  case AFTER_SECOND_SYNC:
374  command = SYNC2;
375  packet.Build(&command, 1);
376  packet.Send(this->psos_fd);
377  break;
378  default:
379  ROS_WARN("P2OS::Setup():shouldn't be here...");
380  break;
381  }
382  usleep(P2OS_CYCLETIME_USEC);
383 
384  if(receivedpacket.Receive(this->psos_fd))
385  {
386  if((psos_state == NO_SYNC) && (num_sync_attempts >= 0))
387  {
388  num_sync_attempts--;
389  usleep(P2OS_CYCLETIME_USEC);
390  continue;
391  }
392  else
393  {
394  // couldn't connect; try different speed.
395  if(++currbaud < numbauds)
396  {
397  cfsetispeed(&term, bauds[currbaud]);
398  cfsetospeed(&term, bauds[currbaud]);
399  if( tcsetattr(this->psos_fd, TCSAFLUSH, &term ) < 0 )
400  {
401  ROS_ERROR("P2OS::Setup():tcsetattr():");
402  close(this->psos_fd);
403  this->psos_fd = -1;
404  return(1);
405  }
406 
407  if(tcflush(this->psos_fd, TCIOFLUSH ) < 0 )
408  {
409  ROS_ERROR("P2OS::Setup():tcflush():");
410  close(this->psos_fd);
411  this->psos_fd = -1;
412  return(1);
413  }
414  num_sync_attempts = 3;
415  continue;
416  }
417  else
418  {
419  // tried all speeds; bail
420  break;
421  }
422  }
423  }
424  switch(receivedpacket.packet[3])
425  {
426  case SYNC0:
427  ROS_INFO( "SYNC0" );
428  psos_state = AFTER_FIRST_SYNC;
429  break;
430  case SYNC1:
431  ROS_INFO( "SYNC1" );
432  psos_state = AFTER_SECOND_SYNC;
433  break;
434  case SYNC2:
435  ROS_INFO( "SYNC2" );
436  psos_state = READY;
437  break;
438  default:
439  // maybe P2OS is still running from last time. let's try to CLOSE
440  // and reconnect
441  if(!sent_close)
442  {
443  ROS_DEBUG("sending CLOSE");
444  command = CLOSE;
445  packet.Build( &command, 1);
446  packet.Send(this->psos_fd);
447  sent_close = true;
448  usleep(2*P2OS_CYCLETIME_USEC);
449  tcflush(this->psos_fd,TCIFLUSH);
450  psos_state = NO_SYNC;
451  }
452  break;
453  }
454  usleep(P2OS_CYCLETIME_USEC);
455  }
456  if(psos_state != READY)
457  {
458  if(this->psos_use_tcp)
459  ROS_INFO("Couldn't synchronize with P2OS.\n"
460  " Most likely because the robot is not connected %s %s",
461  this->psos_use_tcp ? "to the ethernet-serial bridge device " : "to the serial port",
462  this->psos_use_tcp ? this->psos_tcp_host.c_str() : this->psos_serial_port.c_str());
463  close(this->psos_fd);
464  this->psos_fd = -1;
465  return(1);
466  }
467  cnt = 4;
468  cnt += snprintf(name, sizeof(name), "%s", &receivedpacket.packet[cnt]);
469  cnt++;
470  cnt += snprintf(type, sizeof(type), "%s", &receivedpacket.packet[cnt]);
471  cnt++;
472  cnt += snprintf(subtype, sizeof(subtype), "%s", &receivedpacket.packet[cnt]);
473  cnt++;
474 
475  std::string hwID = std::string( name ) + std::string(": ") + std::string(type) + std::string("/") + std::string( subtype );
476  diagnostic_.setHardwareID(hwID);
477 
478  command = OPEN;
479  packet.Build(&command, 1);
480  packet.Send(this->psos_fd);
481  usleep(P2OS_CYCLETIME_USEC);
482  command = PULSE;
483  packet.Build(&command, 1);
484  packet.Send(this->psos_fd);
485  usleep(P2OS_CYCLETIME_USEC);
486 
487  ROS_INFO("Done.\n Connected to %s, a %s %s", name, type, subtype);
488 
489  // now, based on robot type, find the right set of parameters
490  for(i=0;i<PLAYER_NUM_ROBOT_TYPES;i++)
491  {
492  if(!strcasecmp(PlayerRobotParams[i].Class.c_str(),type) &&
493  !strcasecmp(PlayerRobotParams[i].Subclass.c_str(),subtype))
494  {
495  param_idx = i;
496  break;
497  }
498  }
499  if(i == PLAYER_NUM_ROBOT_TYPES)
500  {
501  ROS_WARN("P2OS: Warning: couldn't find parameters for this robot; "
502  "using defaults");
503  param_idx = 0;
504  }
505 
506  //sleep(1);
507 
508  // first, receive a packet so we know we're connected.
509  if(!sippacket)
510  {
511  sippacket = new SIP(param_idx);
512  }
513 /*
514  sippacket->x_offset = 0;
515  sippacket->y_offset = 0;
516  sippacket->angle_offset = 0;
517 
518  SendReceive((P2OSPacket*)NULL,false);
519 */
520  // turn off the sonars at first
521  this->ToggleSonarPower(0);
522  // if requested, set max accel/decel limits
523  P2OSPacket accel_packet;
524  unsigned char accel_command[4];
525  if(this->motor_max_trans_accel > 0)
526  {
527  accel_command[0] = SETA;
528  accel_command[1] = ARGINT;
529  accel_command[2] = this->motor_max_trans_accel & 0x00FF;
530  accel_command[3] = (this->motor_max_trans_accel & 0xFF00) >> 8;
531  accel_packet.Build(accel_command, 4);
532  this->SendReceive(&accel_packet,false);
533  }
534 
535  if(this->motor_max_trans_decel < 0)
536  {
537  accel_command[0] = SETA;
538  accel_command[1] = ARGNINT;
539  accel_command[2] = abs(this->motor_max_trans_decel) & 0x00FF;
540  accel_command[3] = (abs(this->motor_max_trans_decel) & 0xFF00) >> 8;
541  accel_packet.Build(accel_command, 4);
542  this->SendReceive(&accel_packet,false);
543  }
544  if(this->motor_max_rot_accel > 0)
545  {
546  accel_command[0] = SETRA;
547  accel_command[1] = ARGINT;
548  accel_command[2] = this->motor_max_rot_accel & 0x00FF;
549  accel_command[3] = (this->motor_max_rot_accel & 0xFF00) >> 8;
550  accel_packet.Build(accel_command, 4);
551  this->SendReceive(&accel_packet,false);
552  }
553  if(this->motor_max_rot_decel < 0)
554  {
555  accel_command[0] = SETRA;
556  accel_command[1] = ARGNINT;
557  accel_command[2] = abs(this->motor_max_rot_decel) & 0x00FF;
558  accel_command[3] = (abs(this->motor_max_rot_decel) & 0xFF00) >> 8;
559  accel_packet.Build(accel_command, 4);
560  this->SendReceive(&accel_packet,false);
561  }
562 
563 
564  // if requested, change PID settings
565  P2OSPacket pid_packet;
566  unsigned char pid_command[4];
567  if(this->rot_kp >= 0)
568  {
569  pid_command[0] = ROTKP;
570  pid_command[1] = ARGINT;
571  pid_command[2] = this->rot_kp & 0x00FF;
572  pid_command[3] = (this->rot_kp & 0xFF00) >> 8;
573  pid_packet.Build(pid_command, 4);
574  this->SendReceive(&pid_packet);
575  }
576  if(this->rot_kv >= 0)
577  {
578  pid_command[0] = ROTKV;
579  pid_command[1] = ARGINT;
580  pid_command[2] = this->rot_kv & 0x00FF;
581  pid_command[3] = (this->rot_kv & 0xFF00) >> 8;
582  pid_packet.Build(pid_command, 4);
583  this->SendReceive(&pid_packet);
584  }
585  if(this->rot_ki >= 0)
586  {
587  pid_command[0] = ROTKI;
588  pid_command[1] = ARGINT;
589  pid_command[2] = this->rot_ki & 0x00FF;
590  pid_command[3] = (this->rot_ki & 0xFF00) >> 8;
591  pid_packet.Build(pid_command, 4);
592  this->SendReceive(&pid_packet);
593  }
594  if(this->trans_kp >= 0)
595  {
596  pid_command[0] = TRANSKP;
597  pid_command[1] = ARGINT;
598  pid_command[2] = this->trans_kp & 0x00FF;
599  pid_command[3] = (this->trans_kp & 0xFF00) >> 8;
600  pid_packet.Build(pid_command, 4);
601  this->SendReceive(&pid_packet);
602  }
603  if(this->trans_kv >= 0)
604  {
605  pid_command[0] = TRANSKV;
606  pid_command[1] = ARGINT;
607  pid_command[2] = this->trans_kv & 0x00FF;
608  pid_command[3] = (this->trans_kv & 0xFF00) >> 8;
609  pid_packet.Build(pid_command, 4);
610  this->SendReceive(&pid_packet);
611  }
612  if(this->trans_ki >= 0)
613  {
614  pid_command[0] = TRANSKI;
615  pid_command[1] = ARGINT;
616  pid_command[2] = this->trans_ki & 0x00FF;
617  pid_command[3] = (this->trans_ki & 0xFF00) >> 8;
618  pid_packet.Build(pid_command, 4);
619  this->SendReceive(&pid_packet);
620  }
621 
622 
623  // if requested, change bumper-stall behavior
624  // 0 = don't stall
625  // 1 = stall on front bumper contact
626  // 2 = stall on rear bumper contact
627  // 3 = stall on either bumper contact
628  if(this->bumpstall >= 0)
629  {
630  if(this->bumpstall > 3)
631  ROS_INFO("ignoring bumpstall value %d; should be 0, 1, 2, or 3",
632  this->bumpstall);
633  else
634  {
635  ROS_INFO("setting bumpstall to %d", this->bumpstall);
636  P2OSPacket bumpstall_packet;;
637  unsigned char bumpstall_command[4];
638  bumpstall_command[0] = BUMP_STALL;
639  bumpstall_command[1] = ARGINT;
640  bumpstall_command[2] = (unsigned char)this->bumpstall;
641  bumpstall_command[3] = 0;
642  bumpstall_packet.Build(bumpstall_command, 4);
643  this->SendReceive(&bumpstall_packet,false);
644  }
645  }
646 
647  // Turn on the sonar
648  if(use_sonar_) {
649  this->ToggleSonarPower(1);
650  ROS_DEBUG("Sonar array powered on.");
651  }
652  ptz_.setup();
653 
654  return(0);
655 }
656 
658 {
659  unsigned char command[20],buffer[20];
660  P2OSPacket packet;
661 
662  if (ptz_.isOn())
663  {
664  ptz_.shutdown();
665  }
666 
667  memset(buffer,0,20);
668 
669  if(this->psos_fd == -1)
670  return -1;
671 
672  command[0] = STOP;
673  packet.Build(command, 1);
674  packet.Send(this->psos_fd);
675  usleep(P2OS_CYCLETIME_USEC);
676 
677  command[0] = CLOSE;
678  packet.Build(command, 1);
679  packet.Send(this->psos_fd);
680  usleep(P2OS_CYCLETIME_USEC);
681 
682  close(this->psos_fd);
683  this->psos_fd = -1;
684  ROS_INFO("P2OS has been shutdown");
685  delete this->sippacket;
686  this->sippacket = NULL;
687 
688  return 0;
689 }
690 
691 
692 void
694 {
695 
696  p2os_data.position.header.stamp = ts;
697  pose_pub_.publish( p2os_data.position );
698  p2os_data.odom_trans.header.stamp = ts;
699  odom_broadcaster.sendTransform( p2os_data.odom_trans );
700 
701  p2os_data.batt.header.stamp = ts;
702  batt_pub_.publish( p2os_data.batt );
703  mstate_pub_.publish( p2os_data.motors );
704 
705  // put sonar data
706  p2os_data.sonar.header.stamp = ts;
707  sonar_pub_.publish( p2os_data.sonar );
708 
709  // put aio data
710  aio_pub_.publish( p2os_data.aio);
711  // put dio data
712  dio_pub_.publish( p2os_data.dio);
713 
714  // put gripper and lift data
715  grip_state_pub_.publish( p2os_data.gripper );
716  ptz_state_pub_.publish( ptz_.getCurrentState() );
717 
718  // put bumper data
719  // put compass data
720 
721 }
722 
723 /* send the packet, then receive and parse an SIP */
724 int P2OSNode::SendReceive(P2OSPacket* pkt, bool publish_data)
725 {
726  P2OSPacket packet;
727 
728  if((this->psos_fd >= 0) && this->sippacket)
729  {
730  if(pkt)
731  pkt->Send(this->psos_fd);
732 
733  /* receive a packet */
734  pthread_testcancel();
735  if(packet.Receive(this->psos_fd))
736  {
737  ROS_ERROR("RunPsosThread(): Receive errored");
738  pthread_exit(NULL);
739  }
740 
741  if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
742  (packet.packet[3] == 0x30 || packet.packet[3] == 0x31 ||
743  packet.packet[3] == 0x32 || packet.packet[3] == 0x33 ||
744  packet.packet[3] == 0x34))
745  {
746 
747  /* It is a server packet, so process it */
748  this->sippacket->ParseStandard( &packet.packet[3] );
749  this->sippacket->FillStandard(&(this->p2os_data));
750 
751  if(publish_data)
752  this->StandardSIPPutData(packet.timestamp);
753  }
754  else if(packet.packet[0] == 0xFA && packet.packet[1] == 0xFB &&
755  packet.packet[3] == SERAUX)
756  {
757  // This is an AUX serial packet
758  if(ptz_.isOn())
759  {
760  int len = packet.packet[2] - 3;
761  if (ptz_.cb_.gotPacket())
762  {
763  ROS_ERROR("PTZ got a message, but alread has the complete packet.");
764  }
765  else
766  {
767  for (int i=4; i < 4+len; ++i)
768  {
769  ptz_.cb_.putOnBuf(packet.packet[i]);
770  }
771  }
772  }
773  }
774  else
775  {
776  ROS_ERROR("Received other packet!");
777  packet.PrintHex();
778  }
779  }
780 
781  return(0);
782 }
783 
785 {
786  diagnostic_.update();
787 }
788 
789 void P2OSNode::check_voltage( diagnostic_updater::DiagnosticStatusWrapper &stat )
790 {
791  double voltage = sippacket->battery / 10.0;
792  if( voltage < 11.0 )
793  {
794  stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "battery voltage critically low" );
795  }
796  else if( voltage < 11.75 )
797  {
798  stat.summary( diagnostic_msgs::DiagnosticStatus::WARN, "battery voltage getting low" );
799 
800  }
801  else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "battery voltage OK" );
802 
803  stat.add("voltage", voltage );
804 }
805 
806 void P2OSNode::check_stall( diagnostic_updater::DiagnosticStatusWrapper &stat )
807 {
809  {
810  stat.summary( diagnostic_msgs::DiagnosticStatus::ERROR, "wheel stalled" );
811  }
812  else stat.summary( diagnostic_msgs::DiagnosticStatus::OK, "no wheel stall" );
813 
814  stat.add("left wheel stall", sippacket->lwstall );
815  stat.add("right wheel stall", sippacket->rwstall );
816 }
817 
819 {
820  P2OSPacket pkt;
821  unsigned char p2oscommand[4];
822 
823  if(this->sippacket)
824  {
825  this->sippacket->rawxpos = 0;
826  this->sippacket->rawypos = 0;
827  this->sippacket->xpos = 0;
828  this->sippacket->ypos = 0;
829  p2oscommand[0] = SETO;
830  p2oscommand[1] = ARGINT;
831  pkt.Build(p2oscommand, 2);
832  this->SendReceive(&pkt,false);
833  ROS_INFO("resetting raw positions" );
834  }
835 }
836 
837 /* toggle sonars on/off, according to val */
838 void P2OSNode::ToggleSonarPower(unsigned char val)
839 {
840  unsigned char command[4];
841  P2OSPacket packet;
842 
843  command[0] = SONAR;
844  command[1] = ARGINT;
845  command[2] = val;
846  command[3] = 0;
847  packet.Build(command, 4);
848  SendReceive(&packet,false);
849 }
850 
856 void P2OSNode::ToggleMotorPower(unsigned char val)
857 {
858  unsigned char command[4];
859  P2OSPacket packet;
860  ROS_INFO( "motor state: %d\n", p2os_data.motors.state );
861  p2os_data.motors.state = (int) val;
862  command[0] = ENABLE;
863  command[1] = ARGINT;
864  command[2] = val;
865  command[3] = 0;
866  packet.Build(command, 4);
867  SendReceive(&packet,false);
868 }
869 
871 // Actarray stuff
873 
874 // Ticks to degrees from the ARIA software
876 inline double P2OSNode::TicksToDegrees (int joint, unsigned char ticks)
877 {
878  if ((joint < 0) || (joint >= sippacket->armNumJoints))
879  return 0;
880 
881  double result;
882  int pos = ticks - sippacket->armJoints[joint].centre;
883  result = 90.0 / static_cast<double> (sippacket->armJoints[joint].ticksPer90);
884  result = result * pos;
885  if ((joint >= 0) && (joint <= 2))
886  result = -result;
887 
888  return result;
889 }
890 
891 // Degrees to ticks from the ARIA software
893 inline unsigned char P2OSNode::DegreesToTicks (int joint, double degrees)
894 {
895  double val;
896 
897  if ((joint < 0) || (joint >= sippacket->armNumJoints))
898  return 0;
899 
900  val = static_cast<double> (sippacket->armJoints[joint].ticksPer90) * degrees / 90.0;
901  val = round (val);
902  if ((joint >= 0) && (joint <= 2))
903  val = -val;
904  val += sippacket->armJoints[joint].centre;
905 
906  if (val < sippacket->armJoints[joint].min)
907  return sippacket->armJoints[joint].min;
908  else if (val > sippacket->armJoints[joint].max)
909  return sippacket->armJoints[joint].max;
910  else
911  return static_cast<int> (round (val));
912 }
913 
915 inline double P2OSNode::TicksToRadians (int joint, unsigned char ticks)
916 {
917  double result = DTOR (TicksToDegrees (joint, ticks));
918  return result;
919 }
920 
922 inline unsigned char P2OSNode::RadiansToTicks (int joint, double rads)
923 {
924  unsigned char result = static_cast<unsigned char> (DegreesToTicks (joint, RTOD (rads)));
925  return result;
926 }
927 
929 inline double P2OSNode::RadsPerSectoSecsPerTick (int joint, double speed)
930 {
931  double degs = RTOD (speed);
932  double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
933  double ticksPerSec = degs * ticksPerDeg;
934  double secsPerTick = 1000.0f / ticksPerSec;
935 
936  if (secsPerTick > 127)
937  return 127;
938  else if (secsPerTick < 1)
939  return 1;
940  return secsPerTick;
941 }
942 
944 inline double P2OSNode::SecsPerTicktoRadsPerSec (int joint, double msecs)
945 {
946  double ticksPerSec = 1.0 / (static_cast<double> (msecs) / 1000.0);
947  double ticksPerDeg = static_cast<double> (sippacket->armJoints[joint].ticksPer90) / 90.0f;
948  double degs = ticksPerSec / ticksPerDeg;
949  double rads = DTOR (degs);
950 
951  return rads;
952 }
953 
955 {
956  unsigned char command;
957  P2OSPacket packet;
958 
959  command = PULSE;
960  packet.Build(&command, 1);
961  SendReceive(&packet);
962 }
std::string psos_tcp_host
Definition: p2os.h:154
double TicksToDegrees(int joint, unsigned char ticks)
Convert ticks to degrees.
Definition: p2os.cc:876
short motor_max_trans_decel
Minimum translational acceleration in Meters per second per second.
Definition: p2os.h:179
diagnostic_updater::Updater diagnostic_
Definition: p2os.h:141
int rot_kv
Definition: p2os.h:162
void PrintHex()
Definition: packet.cc:41
virtual ~P2OSNode()
Definition: p2os.cc:130
ros::Publisher aio_pub_
Definition: p2os.h:144
int motor_max_speed
Maximum motor speed in Meters per second.
Definition: p2os.h:173
bool rwstall
Definition: sip.h:62
#define SYNC0
Definition: robot_params.h:85
#define RTOD(a)
Definition: robot_params.h:231
int rot_kp
Definition: p2os.h:162
p2os_msgs::PTZState getCurrentState()
Definition: p2os_ptz.h:162
bool motor_dirty
Definition: p2os.h:158
int trans_kv
Definition: p2os.h:162
#define DEFAULT_P2OS_TCP_REMOTE_HOST
Definition: robot_params.h:226
void ToggleMotorPower(unsigned char val)
Toggle motors on/off.
Definition: p2os.cc:856
ros::Publisher mstate_pub_
Definition: p2os.h:144
int SendReceive(P2OSPacket *pkt, bool publish_data=true)
Definition: p2os.cc:724
unsigned char centre
Definition: sip.h:36
p2os_msgs::MotorState cmdmotor_state_
Motor state publisher.
Definition: p2os.h:198
#define SYNC1
Definition: robot_params.h:86
p2os_msgs::SonarArray sonar
Container for sonar data.
Definition: p2os.h:65
double RadsPerSectoSecsPerTick(int joint, double speed)
Convert radians per second to radians per encoder tick.
Definition: p2os.cc:929
int xpos
Definition: sip.h:69
int psos_tcp_port
Definition: p2os.h:157
void shutdown()
Definition: p2os_ptz.cpp:151
#define ARGNINT
Definition: robot_params.h:203
ros::Publisher dio_pub_
Definition: p2os.h:144
#define DEFAULT_P2OS_TCP_REMOTE_PORT
Definition: robot_params.h:227
int rot_ki
Definition: p2os.h:162
bool use_sonar_
Use the sonar array?
Definition: p2os.h:190
#define DTOR(a)
Definition: robot_params.h:230
SIP * sippacket
Definition: p2os.h:152
unsigned char packet[PACKET_LEN]
Definition: packet.h:36
unsigned char RadiansToTicks(int joint, double rads)
Convert radians to ticks.
Definition: p2os.cc:922
void updateDiagnostics()
Definition: p2os.cc:784
p2os_msgs::AIO aio
Analog In/Out.
Definition: p2os.h:69
ros::Time timestamp
Definition: packet.h:38
bool isOn() const
Definition: p2os_ptz.h:161
ros::NodeHandle n
Node Handler used for publication of data.
Definition: p2os.h:137
void check_voltage(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: p2os.cc:789
unsigned short rawxpos
Definition: sip.h:65
ArmJoint * armJoints
Definition: sip.h:90
#define PLAYER_NUM_ROBOT_TYPES
Definition: robot_params.h:67
std::string psos_serial_port
Definition: p2os.h:153
int joystick
Use Joystick?
Definition: p2os.h:167
void gripperCallback(const p2os_msgs::GripperStateConstPtr &msg)
Definition: p2os.cc:267
p2os_msgs::GripperState gripper
Provides the state of the gripper.
Definition: p2os.h:63
geometry_msgs::TransformStamped odom_trans
Transformed odometry frame.
Definition: p2os.h:71
bool gotPacket()
Definition: p2os_ptz.cpp:1052
ros::Publisher sonar_pub_
Definition: p2os.h:144
void check_and_set_gripper_state()
Definition: p2os.cc:159
tf::TransformBroadcaster odom_broadcaster
Definition: p2os.h:149
#define MOTOR_DEF_MAX_SPEED
Definition: robot_params.h:70
RobotParams_t PlayerRobotParams[]
#define ARGINT
Definition: robot_params.h:202
#define SYNC2
Definition: robot_params.h:87
void ParseStandard(unsigned char *buffer)
Definition: sip.cc:349
void SendPulse(void)
Definition: p2os.cc:954
void putOnBuf(unsigned char c)
Definition: p2os_ptz.cpp:1001
circbuf cb_
Definition: p2os_ptz.h:168
diagnostic_updater::DiagnosedPublisher< p2os_msgs::BatteryState > batt_pub_
Definition: p2os.h:143
unsigned short rawypos
Definition: sip.h:66
int ypos
Definition: sip.h:69
int Build(unsigned char *data, unsigned char datasize)
Definition: packet.cc:134
int bumpstall
Stall I hit a wall?
Definition: p2os.h:165
short motor_max_rot_accel
Maximum rotational acceleration in radians per second per second.
Definition: p2os.h:181
double pulse
Pulse time.
Definition: p2os.h:185
p2os_msgs::GripperState gripper_state_
Gripper state publisher.
Definition: p2os.h:200
int trans_ki
Definition: p2os.h:162
void callback(const p2os_msgs::PTZStateConstPtr &msg)
Definition: p2os_ptz.cpp:162
ros::Publisher grip_state_pub_
Definition: p2os.h:144
double desired_freq
Definition: p2os.h:186
int Setup()
Setup the robot for use. Communicates with the robot directly.
Definition: p2os.cc:273
bool vel_dirty
Definition: p2os.h:158
bool psos_use_tcp
Definition: p2os.h:156
unsigned char max
Definition: sip.h:37
ros::Time veltime
Definition: p2os.h:150
P2OSNode(ros::NodeHandle n)
P2OS robot driver node.
Definition: p2os.cc:32
ros::Subscriber ptz_cmd_sub_
Definition: p2os.h:147
P2OSPtz ptz_
Definition: p2os.h:192
void cmdmotor_state(const p2os_msgs::MotorStateConstPtr &)
Definition: p2os.cc:134
int trans_kp
Definition: p2os.h:162
ros::Subscriber cmdvel_sub_
Definition: p2os.h:147
void ResetRawPositions()
Definition: p2os.cc:818
unsigned char ticksPer90
Definition: sip.h:38
p2os_msgs::BatteryState batt
Provides the battery voltage.
Definition: p2os.h:59
int motor_max_turnspeed
Maximum turn speed in radians per second.
Definition: p2os.h:175
int Shutdown()
Prepare for shutdown.
Definition: p2os.cc:657
double lastPulseTime
Last time the node received or sent a pulse.
Definition: p2os.h:188
void initialize_robot_params(void)
void FillStandard(ros_p2os_data_t *data)
Definition: sip.cc:38
#define P2OS_CYCLETIME_USEC
Definition: robot_params.h:78
Definition: sip.h:54
unsigned char min
Definition: sip.h:35
int Receive(int fd)
Definition: packet.cc:81
int psos_fd
Definition: p2os.h:155
unsigned char battery
Definition: sip.h:64
ros::Subscriber gripper_sub_
Definition: p2os.h:147
bool lwstall
Definition: sip.h:62
bool gripper_dirty_
Definition: p2os.h:159
unsigned char armNumJoints
Definition: sip.h:89
ros::Subscriber cmdmstate_sub_
Definition: p2os.h:147
void StandardSIPPutData(ros::Time ts)
Definition: p2os.cc:693
void ToggleSonarPower(unsigned char val)
Definition: p2os.cc:838
#define SERAUX
Definition: robot_params.h:194
int setup()
Definition: p2os_ptz.cpp:56
int param_idx
Definition: p2os.h:160
short motor_max_trans_accel
Maximum translational acceleration in Meters per second per second.
Definition: p2os.h:177
double TicksToRadians(int joint, unsigned char ticks)
Convert ticks to radians.
Definition: p2os.cc:915
void check_and_set_vel()
Definition: p2os.cc:210
short motor_max_rot_decel
Minimum rotational acceleration in Meters per second per second.
Definition: p2os.h:183
ros_p2os_data_t p2os_data
sensor data container
Definition: p2os.h:202
geometry_msgs::Twist cmdvel_
Command Velocity subscriber.
Definition: p2os.h:196
#define DEFAULT_P2OS_PORT
Definition: robot_params.h:225
p2os_msgs::MotorState motors
Provides the state of the motors (enabled or disabled)
Definition: p2os.h:61
int radio_modemp
Definition: p2os.h:170
double SecsPerTicktoRadsPerSec(int joint, double secs)
Convert Seconds per encoder tick to radians per second.
Definition: p2os.cc:944
unsigned char DegreesToTicks(int joint, double degrees)
convert degrees to ticks
Definition: p2os.cc:893
int Send(int fd)
Definition: packet.cc:162
void check_and_set_motor_state()
Definition: p2os.cc:140
void cmdvel_cb(const geometry_msgs::TwistConstPtr &)
Definition: p2os.cc:187
ros::Publisher ptz_state_pub_
Definition: p2os.h:144
nav_msgs::Odometry position
Provides the position of the robot.
Definition: p2os.h:57
int direct_wheel_vel_control
Control wheel velocities individually?
Definition: p2os.h:169
#define MOTOR_DEF_MAX_TURNSPEED
Definition: robot_params.h:71
void check_stall(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: p2os.cc:806
p2os_msgs::DIO dio
Digital In/Out.
Definition: p2os.h:67
ros::Publisher pose_pub_
Definition: p2os.h:146


p2os_driver
Author(s): Hunter Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Wed Jun 25 2014 09:37:15