23 #include <geometry_msgs/Pose.h> 24 #include <geometry_msgs/PoseStamped.h> 26 #include <p2os_msgs/MotorState.h> 31 int main(
int argc,
char ** argv)
58 lastTime = currentTime;
73 ROS_WARN(
"p2os shutdown failed... your robot might be heading for the wall?");
int main(int argc, char **argv)
int SendReceive(P2OSPacket *pkt, bool publish_data=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void check_and_set_gripper_state()
int Setup()
Setup the robot for use. Communicates with the robot directly.
int Shutdown()
Prepare for shutdown.
ROSCPP_DECL void spinOnce()
void check_and_set_motor_state()