P2OSNode Class Reference

#include <p2os.h>

List of all members.

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_driver::MotorStateConstPtr &)
void cmdvel_cb (const geometry_msgs::TwistConstPtr &)
unsigned char DegreesToTicks (int joint, double degrees)
double get_pulse ()
void gripperCallback (const p2os_driver::GripperStateConstPtr &msg)
 P2OSNode (ros::NodeHandle n)
unsigned char RadiansToTicks (int joint, double rads)
double RadsPerSectoSecsPerTick (int joint, double speed)
void ResetRawPositions ()
double SecsPerTicktoRadsPerSec (int joint, double secs)
void SendPulse (void)
int SendReceive (P2OSPacket *pkt, bool publish_data=true)
int Setup ()
int Shutdown ()
void StandardSIPPutData (ros::Time ts)
double TicksToDegrees (int joint, unsigned char ticks)
double TicksToRadians (int joint, unsigned char ticks)
void ToggleMotorPower (unsigned char val)
void ToggleSonarPower (unsigned char val)
void updateDiagnostics ()
virtual ~P2OSNode ()

Public Attributes

p2os_driver::MotorState cmdmotor_state_
geometry_msgs::Twist cmdvel_
p2os_driver::GripperState gripper_state_
ros_p2os_data_t p2os_data

Protected Attributes

ros::Publisher aio_pub_
diagnostic_updater::DiagnosedPublisher
< p2os_driver::BatteryState
batt_pub_
int bumpstall
ros::Subscriber cmdmstate_sub_
ros::Subscriber cmdvel_sub_
double desired_freq
diagnostic_updater::Updater diagnostic_
ros::Publisher dio_pub_
int direct_wheel_vel_control
ros::Publisher grip_state_pub_
bool gripper_dirty_
ros::Subscriber gripper_sub_
int joystick
double lastPulseTime
bool motor_dirty
short motor_max_rot_accel
short motor_max_rot_decel
int motor_max_speed
short motor_max_trans_accel
short motor_max_trans_decel
int motor_max_turnspeed
ros::Publisher mstate_pub_
ros::NodeHandle n
ros::NodeHandle nh_private
tf::TransformBroadcaster odom_broadcaster
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
int radio_modemp
int rot_ki
int rot_kp
int rot_kv
SIPsippacket
ros::Publisher sonar_pub_
int trans_ki
int trans_kp
int trans_kv
bool use_sonar_
bool vel_dirty
ros::Time veltime

Detailed Description

Definition at line 73 of file p2os.h.


Constructor & Destructor Documentation

P2OSNode::P2OSNode ( ros::NodeHandle  n  ) 

Definition at line 32 of file p2os.cc.

P2OSNode::~P2OSNode (  )  [virtual]

Definition at line 124 of file p2os.cc.


Member Function Documentation

void P2OSNode::check_and_set_gripper_state (  ) 

Definition at line 156 of file p2os.cc.

void P2OSNode::check_and_set_motor_state (  ) 

Definition at line 136 of file p2os.cc.

void P2OSNode::check_and_set_vel (  ) 

Definition at line 209 of file p2os.cc.

void P2OSNode::check_stall ( diagnostic_updater::DiagnosticStatusWrapper &  stat  ) 

Definition at line 811 of file p2os.cc.

void P2OSNode::check_voltage ( diagnostic_updater::DiagnosticStatusWrapper &  stat  ) 

Definition at line 793 of file p2os.cc.

void P2OSNode::cmdmotor_state ( const p2os_driver::MotorStateConstPtr msg  ) 

Definition at line 129 of file p2os.cc.

void P2OSNode::cmdvel_cb ( const geometry_msgs::TwistConstPtr &  msg  ) 

Definition at line 185 of file p2os.cc.

unsigned char P2OSNode::DegreesToTicks ( int  joint,
double  degrees 
) [inline]

Definition at line 895 of file p2os.cc.

double P2OSNode::get_pulse (  )  [inline]

Definition at line 109 of file p2os.h.

void P2OSNode::gripperCallback ( const p2os_driver::GripperStateConstPtr msg  ) 

Definition at line 266 of file p2os.cc.

unsigned char P2OSNode::RadiansToTicks ( int  joint,
double  rads 
) [inline]

Definition at line 922 of file p2os.cc.

double P2OSNode::RadsPerSectoSecsPerTick ( int  joint,
double  speed 
) [inline]

Definition at line 928 of file p2os.cc.

void P2OSNode::ResetRawPositions (  ) 

Definition at line 824 of file p2os.cc.

double P2OSNode::SecsPerTicktoRadsPerSec ( int  joint,
double  secs 
) [inline]

Definition at line 942 of file p2os.cc.

void P2OSNode::SendPulse ( void   ) 

Definition at line 952 of file p2os.cc.

int P2OSNode::SendReceive ( P2OSPacket pkt,
bool  publish_data = true 
)

Definition at line 726 of file p2os.cc.

int P2OSNode::Setup (  ) 

Definition at line 273 of file p2os.cc.

int P2OSNode::Shutdown (  ) 

Definition at line 658 of file p2os.cc.

void P2OSNode::StandardSIPPutData ( ros::Time  ts  ) 

Definition at line 694 of file p2os.cc.

double P2OSNode::TicksToDegrees ( int  joint,
unsigned char  ticks 
) [inline]

Definition at line 879 of file p2os.cc.

double P2OSNode::TicksToRadians ( int  joint,
unsigned char  ticks 
) [inline]

Definition at line 916 of file p2os.cc.

void P2OSNode::ToggleMotorPower ( unsigned char  val  ) 

Definition at line 860 of file p2os.cc.

void P2OSNode::ToggleSonarPower ( unsigned char  val  ) 

Definition at line 845 of file p2os.cc.

void P2OSNode::updateDiagnostics (  ) 

Definition at line 787 of file p2os.cc.


Member Data Documentation

ros::Publisher P2OSNode::aio_pub_ [protected]

Definition at line 122 of file p2os.h.

diagnostic_updater::DiagnosedPublisher<p2os_driver::BatteryState> P2OSNode::batt_pub_ [protected]

Definition at line 121 of file p2os.h.

int P2OSNode::bumpstall [protected]

Definition at line 141 of file p2os.h.

Definition at line 159 of file p2os.h.

ros::Subscriber P2OSNode::cmdmstate_sub_ [protected]

Definition at line 124 of file p2os.h.

geometry_msgs::Twist P2OSNode::cmdvel_

Definition at line 158 of file p2os.h.

ros::Subscriber P2OSNode::cmdvel_sub_ [protected]

Definition at line 124 of file p2os.h.

double P2OSNode::desired_freq [protected]

Definition at line 151 of file p2os.h.

diagnostic_updater::Updater P2OSNode::diagnostic_ [protected]

Definition at line 119 of file p2os.h.

ros::Publisher P2OSNode::dio_pub_ [protected]

Definition at line 122 of file p2os.h.

Definition at line 143 of file p2os.h.

ros::Publisher P2OSNode::grip_state_pub_ [protected]

Definition at line 122 of file p2os.h.

bool P2OSNode::gripper_dirty_ [protected]

Definition at line 136 of file p2os.h.

Definition at line 160 of file p2os.h.

ros::Subscriber P2OSNode::gripper_sub_ [protected]

Definition at line 124 of file p2os.h.

int P2OSNode::joystick [protected]

Definition at line 142 of file p2os.h.

double P2OSNode::lastPulseTime [protected]

Definition at line 152 of file p2os.h.

bool P2OSNode::motor_dirty [protected]

Definition at line 135 of file p2os.h.

short P2OSNode::motor_max_rot_accel [protected]

Definition at line 149 of file p2os.h.

short P2OSNode::motor_max_rot_decel [protected]

Definition at line 149 of file p2os.h.

int P2OSNode::motor_max_speed [protected]

Definition at line 146 of file p2os.h.

Definition at line 148 of file p2os.h.

Definition at line 148 of file p2os.h.

Definition at line 147 of file p2os.h.

ros::Publisher P2OSNode::mstate_pub_ [protected]

Definition at line 122 of file p2os.h.

ros::NodeHandle P2OSNode::n [protected]

Definition at line 116 of file p2os.h.

ros::NodeHandle P2OSNode::nh_private [protected]

Definition at line 117 of file p2os.h.

tf::TransformBroadcaster P2OSNode::odom_broadcaster [protected]

Definition at line 126 of file p2os.h.

Definition at line 161 of file p2os.h.

int P2OSNode::param_idx [protected]

Definition at line 137 of file p2os.h.

ros::Publisher P2OSNode::pose_pub_ [protected]

Definition at line 122 of file p2os.h.

int P2OSNode::psos_fd [protected]

Definition at line 132 of file p2os.h.

std::string P2OSNode::psos_serial_port [protected]

Definition at line 130 of file p2os.h.

std::string P2OSNode::psos_tcp_host [protected]

Definition at line 131 of file p2os.h.

int P2OSNode::psos_tcp_port [protected]

Definition at line 134 of file p2os.h.

bool P2OSNode::psos_use_tcp [protected]

Definition at line 133 of file p2os.h.

P2OSPtz P2OSNode::ptz_ [protected]

Definition at line 155 of file p2os.h.

ros::Subscriber P2OSNode::ptz_cmd_sub_ [protected]

Definition at line 124 of file p2os.h.

ros::Publisher P2OSNode::ptz_state_pub_ [protected]

Definition at line 122 of file p2os.h.

double P2OSNode::pulse [protected]

Definition at line 150 of file p2os.h.

int P2OSNode::radio_modemp [protected]

Definition at line 144 of file p2os.h.

int P2OSNode::rot_ki [protected]

Definition at line 139 of file p2os.h.

int P2OSNode::rot_kp [protected]

Definition at line 139 of file p2os.h.

int P2OSNode::rot_kv [protected]

Definition at line 139 of file p2os.h.

SIP* P2OSNode::sippacket [protected]

Definition at line 129 of file p2os.h.

ros::Publisher P2OSNode::sonar_pub_ [protected]

Definition at line 122 of file p2os.h.

int P2OSNode::trans_ki [protected]

Definition at line 139 of file p2os.h.

int P2OSNode::trans_kp [protected]

Definition at line 139 of file p2os.h.

int P2OSNode::trans_kv [protected]

Definition at line 139 of file p2os.h.

bool P2OSNode::use_sonar_ [protected]

Definition at line 153 of file p2os.h.

bool P2OSNode::vel_dirty [protected]

Definition at line 135 of file p2os.h.

ros::Time P2OSNode::veltime [protected]

Definition at line 127 of file p2os.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


p2os_driver
Author(s): dfseifer@usc.edu
autogenerated on Fri Jan 11 09:54:57 2013