#include <p2os.h>
| Public Member Functions | |
| void | check_and_set_gripper_state () | 
| void | check_and_set_motor_state () | 
| void | check_and_set_vel () | 
| void | check_stall (diagnostic_updater::DiagnosticStatusWrapper &stat) | 
| void | check_voltage (diagnostic_updater::DiagnosticStatusWrapper &stat) | 
| void | cmdmotor_state (const p2os_msgs::MotorStateConstPtr &) | 
| void | cmdvel_cb (const geometry_msgs::TwistConstPtr &) | 
| unsigned char | DegreesToTicks (int joint, double degrees) | 
| convert degrees to ticks | |
| double | get_pulse () | 
| void | gripperCallback (const p2os_msgs::GripperStateConstPtr &msg) | 
| P2OSNode (ros::NodeHandle n) | |
| P2OS robot driver node. | |
| unsigned char | RadiansToTicks (int joint, double rads) | 
| Convert radians to ticks. | |
| double | RadsPerSectoSecsPerTick (int joint, double speed) | 
| Convert radians per second to radians per encoder tick. | |
| void | ResetRawPositions () | 
| double | SecsPerTicktoRadsPerSec (int joint, double secs) | 
| Convert Seconds per encoder tick to radians per second. | |
| void | SendPulse (void) | 
| int | SendReceive (P2OSPacket *pkt, bool publish_data=true) | 
| int | Setup () | 
| Setup the robot for use. Communicates with the robot directly. | |
| int | Shutdown () | 
| Prepare for shutdown. | |
| void | StandardSIPPutData (ros::Time ts) | 
| double | TicksToDegrees (int joint, unsigned char ticks) | 
| Convert ticks to degrees. | |
| double | TicksToRadians (int joint, unsigned char ticks) | 
| Convert ticks to radians. | |
| void | ToggleMotorPower (unsigned char val) | 
| Toggle motors on/off. | |
| void | ToggleSonarPower (unsigned char val) | 
| void | updateDiagnostics () | 
| virtual | ~P2OSNode () | 
| Public Attributes | |
| p2os_msgs::MotorState | cmdmotor_state_ | 
| Motor state publisher. | |
| geometry_msgs::Twist | cmdvel_ | 
| Command Velocity subscriber. | |
| p2os_msgs::GripperState | gripper_state_ | 
| Gripper state publisher. | |
| ros_p2os_data_t | p2os_data | 
| sensor data container | |
| Protected Attributes | |
| ros::Publisher | aio_pub_ | 
| std::string | base_link_frame_id | 
| diagnostic_updater::DiagnosedPublisher < p2os_msgs::BatteryState > | batt_pub_ | 
| int | bumpstall | 
| Stall I hit a wall? | |
| ros::Subscriber | cmdmstate_sub_ | 
| ros::Subscriber | cmdvel_sub_ | 
| double | desired_freq | 
| diagnostic_updater::Updater | diagnostic_ | 
| ros::Publisher | dio_pub_ | 
| int | direct_wheel_vel_control | 
| Control wheel velocities individually? | |
| ros::Publisher | grip_state_pub_ | 
| bool | gripper_dirty_ | 
| ros::Subscriber | gripper_sub_ | 
| int | joystick | 
| Use Joystick? | |
| double | lastPulseTime | 
| Last time the node received or sent a pulse. | |
| bool | motor_dirty | 
| short | motor_max_rot_accel | 
| Maximum rotational acceleration in radians per second per second. | |
| short | motor_max_rot_decel | 
| Minimum rotational acceleration in Meters per second per second. | |
| int | motor_max_speed | 
| Maximum motor speed in Meters per second. | |
| short | motor_max_trans_accel | 
| Maximum translational acceleration in Meters per second per second. | |
| short | motor_max_trans_decel | 
| Minimum translational acceleration in Meters per second per second. | |
| int | motor_max_turnspeed | 
| Maximum turn speed in radians per second. | |
| ros::Publisher | mstate_pub_ | 
| ros::NodeHandle | n | 
| Node Handler used for publication of data. | |
| ros::NodeHandle | nh_private | 
| Node Handler used for private data publication. | |
| tf::TransformBroadcaster | odom_broadcaster | 
| std::string | odom_frame_id | 
| int | param_idx | 
| ros::Publisher | pose_pub_ | 
| int | psos_fd | 
| std::string | psos_serial_port | 
| std::string | psos_tcp_host | 
| int | psos_tcp_port | 
| bool | psos_use_tcp | 
| P2OSPtz | ptz_ | 
| ros::Subscriber | ptz_cmd_sub_ | 
| ros::Publisher | ptz_state_pub_ | 
| double | pulse | 
| Pulse time. | |
| int | radio_modemp | 
| int | rot_ki | 
| int | rot_kp | 
| int | rot_kv | 
| SIP * | sippacket | 
| ros::Publisher | sonar_pub_ | 
| int | trans_ki | 
| int | trans_kp | 
| int | trans_kv | 
| bool | use_sonar_ | 
| Use the sonar array? | |
| bool | vel_dirty | 
| ros::Time | veltime | 
| P2OSNode::~P2OSNode | ( | ) |  [virtual] | 
| void P2OSNode::check_and_set_motor_state | ( | ) | 
| void P2OSNode::check_and_set_vel | ( | ) | 
| void P2OSNode::check_stall | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | 
| void P2OSNode::cmdmotor_state | ( | const p2os_msgs::MotorStateConstPtr & | msg | ) | 
| void P2OSNode::cmdvel_cb | ( | const geometry_msgs::TwistConstPtr & | msg | ) | 
| unsigned char P2OSNode::DegreesToTicks | ( | int | joint, | 
| double | degrees | ||
| ) |  [inline] | 
| double P2OSNode::get_pulse | ( | ) |  [inline] | 
| void P2OSNode::gripperCallback | ( | const p2os_msgs::GripperStateConstPtr & | msg | ) | 
| unsigned char P2OSNode::RadiansToTicks | ( | int | joint, | 
| double | rads | ||
| ) |  [inline] | 
| double P2OSNode::RadsPerSectoSecsPerTick | ( | int | joint, | 
| double | speed | ||
| ) |  [inline] | 
| void P2OSNode::ResetRawPositions | ( | ) | 
| double P2OSNode::SecsPerTicktoRadsPerSec | ( | int | joint, | 
| double | secs | ||
| ) |  [inline] | 
| void P2OSNode::SendPulse | ( | void | ) | 
| int P2OSNode::SendReceive | ( | P2OSPacket * | pkt, | 
| bool | publish_data = true | ||
| ) | 
| int P2OSNode::Setup | ( | ) | 
| int P2OSNode::Shutdown | ( | ) | 
| void P2OSNode::StandardSIPPutData | ( | ros::Time | ts | ) | 
| double P2OSNode::TicksToDegrees | ( | int | joint, | 
| unsigned char | ticks | ||
| ) |  [inline] | 
| double P2OSNode::TicksToRadians | ( | int | joint, | 
| unsigned char | ticks | ||
| ) |  [inline] | 
| void P2OSNode::ToggleMotorPower | ( | unsigned char | val | ) | 
| void P2OSNode::ToggleSonarPower | ( | unsigned char | val | ) | 
| void P2OSNode::updateDiagnostics | ( | ) | 
| ros::Publisher P2OSNode::aio_pub_  [protected] | 
| std::string P2OSNode::base_link_frame_id  [protected] | 
| diagnostic_updater::DiagnosedPublisher<p2os_msgs::BatteryState> P2OSNode::batt_pub_  [protected] | 
| int P2OSNode::bumpstall  [protected] | 
| p2os_msgs::MotorState P2OSNode::cmdmotor_state_ | 
| ros::Subscriber P2OSNode::cmdmstate_sub_  [protected] | 
| geometry_msgs::Twist P2OSNode::cmdvel_ | 
| ros::Subscriber P2OSNode::cmdvel_sub_  [protected] | 
| double P2OSNode::desired_freq  [protected] | 
| diagnostic_updater::Updater P2OSNode::diagnostic_  [protected] | 
| ros::Publisher P2OSNode::dio_pub_  [protected] | 
| int P2OSNode::direct_wheel_vel_control  [protected] | 
| ros::Publisher P2OSNode::grip_state_pub_  [protected] | 
| bool P2OSNode::gripper_dirty_  [protected] | 
| p2os_msgs::GripperState P2OSNode::gripper_state_ | 
| ros::Subscriber P2OSNode::gripper_sub_  [protected] | 
| int P2OSNode::joystick  [protected] | 
| double P2OSNode::lastPulseTime  [protected] | 
| bool P2OSNode::motor_dirty  [protected] | 
| short P2OSNode::motor_max_rot_accel  [protected] | 
| short P2OSNode::motor_max_rot_decel  [protected] | 
| int P2OSNode::motor_max_speed  [protected] | 
| short P2OSNode::motor_max_trans_accel  [protected] | 
| short P2OSNode::motor_max_trans_decel  [protected] | 
| int P2OSNode::motor_max_turnspeed  [protected] | 
| ros::Publisher P2OSNode::mstate_pub_  [protected] | 
| ros::NodeHandle P2OSNode::n  [protected] | 
| ros::NodeHandle P2OSNode::nh_private  [protected] | 
| tf::TransformBroadcaster P2OSNode::odom_broadcaster  [protected] | 
| std::string P2OSNode::odom_frame_id  [protected] | 
| int P2OSNode::param_idx  [protected] | 
| ros::Publisher P2OSNode::pose_pub_  [protected] | 
| int P2OSNode::psos_fd  [protected] | 
| std::string P2OSNode::psos_serial_port  [protected] | 
| std::string P2OSNode::psos_tcp_host  [protected] | 
| int P2OSNode::psos_tcp_port  [protected] | 
| bool P2OSNode::psos_use_tcp  [protected] | 
| P2OSPtz P2OSNode::ptz_  [protected] | 
| ros::Subscriber P2OSNode::ptz_cmd_sub_  [protected] | 
| ros::Publisher P2OSNode::ptz_state_pub_  [protected] | 
| double P2OSNode::pulse  [protected] | 
| int P2OSNode::radio_modemp  [protected] | 
| int P2OSNode::rot_ki  [protected] | 
| int P2OSNode::rot_kp  [protected] | 
| int P2OSNode::rot_kv  [protected] | 
| SIP* P2OSNode::sippacket  [protected] | 
| ros::Publisher P2OSNode::sonar_pub_  [protected] | 
| int P2OSNode::trans_ki  [protected] | 
| int P2OSNode::trans_kp  [protected] | 
| int P2OSNode::trans_kv  [protected] | 
| bool P2OSNode::use_sonar_  [protected] | 
| bool P2OSNode::vel_dirty  [protected] | 
| ros::Time P2OSNode::veltime  [protected] |