p2osnode.cpp
Go to the documentation of this file.
1 /*
2  * P2OS for ROS
3  * Copyright (C) 2009 David Feil-Seifer, Brian Gerkey, Kasper Stoy,
4  * Richard Vaughan, & Andrew Howard
5  * Copyright (C) 2018 Hunter L. Allen
6  *
7  * This program is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program; if not, write to the Free Software
19  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
20  */
21 
22 #include <ros/ros.h>
23 #include <geometry_msgs/Pose.h>
24 #include <geometry_msgs/PoseStamped.h>
25 #include <p2os_driver/p2os.hpp>
26 #include <p2os_msgs/MotorState.h>
27 #include <tf/transform_datatypes.h>
28 
29 #include <iostream>
30 
31 int main(int argc, char ** argv)
32 {
33  ros::init(argc, argv, "p2os");
35 
36  P2OSNode * p = new P2OSNode(n);
37 
38  if (p->Setup()) {
39  ROS_ERROR("p2os setup failed...");
40  return -1;
41  }
42 
43  p->ResetRawPositions();
44 
45  ros::Time lastTime;
46 
47  while (ros::ok()) {
48  p->check_and_set_vel();
51 
52  if (p->get_pulse() > 0) {
53  ros::Time currentTime = ros::Time::now();
54  ros::Duration pulseInterval = currentTime - lastTime;
55  if (pulseInterval.toSec() > p->get_pulse()) {
56  ROS_DEBUG("sending pulse");
57  p->SendPulse();
58  lastTime = currentTime;
59  }
60  }
61 
62  // Hack fix to get around the fact that if no commands are sent to the
63  // robot via SendReceive, the driver will never read SIP packets and so
64  // never send data back to clients. We need a better way of doing regular
65  // checks of the serial port - peek in sendreceive, maybe? Because if there
66  // is no data waiting this will sit around waiting until one comes
67  p->SendReceive(NULL, true);
68  p->updateDiagnostics();
69  ros::spinOnce();
70  }
71 
72  if (!p->Shutdown()) {
73  ROS_WARN("p2os shutdown failed... your robot might be heading for the wall?");
74  }
75  delete p;
76 
77  ROS_INFO("Quitting... ");
78  return 0;
79 }
int main(int argc, char **argv)
Definition: p2osnode.cpp:31
int SendReceive(P2OSPacket *pkt, bool publish_data=true)
Definition: p2os.cpp:688
double get_pulse()
Definition: p2os.hpp:127
void updateDiagnostics()
Definition: p2os.cpp:740
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
void check_and_set_gripper_state()
Definition: p2os.cpp:160
void SendPulse(void)
Definition: p2os.cpp:907
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
int Setup()
Setup the robot for use. Communicates with the robot directly.
Definition: p2os.cpp:271
void ResetRawPositions()
Definition: p2os.cpp:768
int Shutdown()
Prepare for shutdown.
Definition: p2os.cpp:623
static Time now()
void check_and_set_vel()
Definition: p2os.cpp:215
ROSCPP_DECL void spinOnce()
void check_and_set_motor_state()
Definition: p2os.cpp:139
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


p2os_driver
Author(s): Hunter L. Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Sat Jun 20 2020 03:29:42