$search
00001 /* 00002 * P2OS for ROS 00003 * Copyright (C) 2009 00004 * David Feil-Seifer, Brian Gerkey, Kasper Stoy, 00005 * Richard Vaughan, & Andrew Howard 00006 * 00007 * 00008 * This program is free software; you can redistribute it and/or modify 00009 * it under the terms of the GNU General Public License as published by 00010 * the Free Software Foundation; either version 2 of the License, or 00011 * (at your option) any later version. 00012 * 00013 * This program is distributed in the hope that it will be useful, 00014 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00015 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00016 * GNU General Public License for more details. 00017 * 00018 * You should have received a copy of the GNU General Public License 00019 * along with this program; if not, write to the Free Software 00020 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00021 * 00022 */ 00023 00024 #ifndef _P2OSDEVICE_H 00025 #define _P2OSDEVICE_H 00026 00027 #include <pthread.h> 00028 #include <sys/time.h> 00029 #include <iostream> 00030 #include <string.h> 00031 00032 #include "packet.h" 00033 #include "robot_params.h" 00034 00035 #include "ros/ros.h" 00036 #include "nav_msgs/Odometry.h" 00037 #include "geometry_msgs/Twist.h" 00038 #include <tf/transform_broadcaster.h> 00039 #include <p2os_driver/BatteryState.h> 00040 #include <p2os_driver/MotorState.h> 00041 #include <p2os_driver/GripperState.h> 00042 #include <p2os_driver/SonarArray.h> 00043 #include <p2os_driver/DIO.h> 00044 #include <p2os_driver/AIO.h> 00045 00046 #include <diagnostic_updater/publisher.h> 00047 #include <diagnostic_updater/diagnostic_updater.h> 00048 00049 typedef struct ros_p2os_data 00050 { 00051 nav_msgs::Odometry position; 00052 p2os_driver::BatteryState batt; 00053 p2os_driver::MotorState motors; 00054 p2os_driver::GripperState gripper; 00055 p2os_driver::SonarArray sonar; 00056 p2os_driver::DIO dio; 00057 p2os_driver::AIO aio; 00058 geometry_msgs::TransformStamped odom_trans; 00059 } ros_p2os_data_t; 00060 00061 // this is here because we need the above typedef's before including it. 00062 #include "sip.h" 00063 #include "kinecalc.h" 00064 00065 #include "p2os_ptz.h" 00066 00067 class SIP; 00068 00069 // Forward declaration of the KineCalc_Base class declared in kinecalc_base.h 00070 //class KineCalc; 00071 00072 00073 class P2OSNode 00074 { 00075 public: 00076 P2OSNode( ros::NodeHandle n ); 00077 virtual ~P2OSNode(); 00078 00079 public: 00080 int Setup(); 00081 int Shutdown(); 00082 00083 int SendReceive(P2OSPacket* pkt, bool publish_data = true ); 00084 00085 void updateDiagnostics(); 00086 00087 void ResetRawPositions(); 00088 void ToggleSonarPower(unsigned char val); 00089 void ToggleMotorPower(unsigned char val); 00090 void StandardSIPPutData(ros::Time ts); 00091 00092 inline double TicksToDegrees (int joint, unsigned char ticks); 00093 inline unsigned char DegreesToTicks (int joint, double degrees); 00094 inline double TicksToRadians (int joint, unsigned char ticks); 00095 inline unsigned char RadiansToTicks (int joint, double rads); 00096 inline double RadsPerSectoSecsPerTick (int joint, double speed); 00097 inline double SecsPerTicktoRadsPerSec (int joint, double secs); 00098 00099 void SendPulse (void); 00100 //void spin(); 00101 void check_and_set_vel(); 00102 void cmdvel_cb( const geometry_msgs::TwistConstPtr &); 00103 00104 void check_and_set_motor_state(); 00105 void cmdmotor_state( const p2os_driver::MotorStateConstPtr &); 00106 00107 void check_and_set_gripper_state(); 00108 void gripperCallback(const p2os_driver::GripperStateConstPtr &msg); 00109 double get_pulse() {return pulse;} 00110 00111 // diagnostic messages 00112 void check_voltage( diagnostic_updater::DiagnosticStatusWrapper &stat ); 00113 void check_stall( diagnostic_updater::DiagnosticStatusWrapper &stat ); 00114 00115 protected: 00116 ros::NodeHandle n; 00117 ros::NodeHandle nh_private; 00118 00119 diagnostic_updater::Updater diagnostic_; 00120 00121 diagnostic_updater::DiagnosedPublisher<p2os_driver::BatteryState> batt_pub_; 00122 ros::Publisher pose_pub_, mstate_pub_, grip_state_pub_, 00123 ptz_state_pub_, sonar_pub_, aio_pub_, dio_pub_; 00124 ros::Subscriber cmdvel_sub_, cmdmstate_sub_, gripper_sub_, ptz_cmd_sub_; 00125 00126 tf::TransformBroadcaster odom_broadcaster; 00127 ros::Time veltime; 00128 00129 SIP* sippacket; 00130 std::string psos_serial_port; 00131 std::string psos_tcp_host; 00132 int psos_fd; 00133 bool psos_use_tcp; 00134 int psos_tcp_port; 00135 bool vel_dirty, motor_dirty; 00136 bool gripper_dirty_; 00137 int param_idx; 00138 // PID settings 00139 int rot_kp, rot_kv, rot_ki, trans_kp, trans_kv, trans_ki; 00140 00141 int bumpstall; // should we change the bumper-stall behavior? 00142 int joystick; 00143 int direct_wheel_vel_control; 00144 int radio_modemp; 00145 00146 int motor_max_speed; 00147 int motor_max_turnspeed; 00148 short motor_max_trans_accel, motor_max_trans_decel; 00149 short motor_max_rot_accel, motor_max_rot_decel; 00150 double pulse; // Pulse time 00151 double desired_freq; 00152 double lastPulseTime; // Last time of sending a pulse or command to the robot 00153 bool use_sonar_; 00154 00155 P2OSPtz ptz_; 00156 00157 public: 00158 geometry_msgs::Twist cmdvel_; 00159 p2os_driver::MotorState cmdmotor_state_; 00160 p2os_driver::GripperState gripper_state_; 00161 ros_p2os_data_t p2os_data; 00162 }; 00163 00164 #endif