$search
#include <p2os.h>
Definition at line 73 of file p2os.h.
P2OSNode::P2OSNode | ( | ros::NodeHandle | n | ) |
void P2OSNode::check_stall | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
void P2OSNode::check_voltage | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
void P2OSNode::cmdmotor_state | ( | const p2os_driver::MotorStateConstPtr & | msg | ) |
void P2OSNode::cmdvel_cb | ( | const geometry_msgs::TwistConstPtr & | msg | ) |
unsigned char P2OSNode::DegreesToTicks | ( | int | joint, | |
double | degrees | |||
) | [inline] |
void P2OSNode::gripperCallback | ( | const p2os_driver::GripperStateConstPtr & | msg | ) |
unsigned char P2OSNode::RadiansToTicks | ( | int | joint, | |
double | rads | |||
) | [inline] |
double P2OSNode::RadsPerSectoSecsPerTick | ( | int | joint, | |
double | speed | |||
) | [inline] |
double P2OSNode::SecsPerTicktoRadsPerSec | ( | int | joint, | |
double | secs | |||
) | [inline] |
int P2OSNode::SendReceive | ( | P2OSPacket * | pkt, | |
bool | publish_data = true | |||
) |
double P2OSNode::TicksToDegrees | ( | int | joint, | |
unsigned char | ticks | |||
) | [inline] |
double P2OSNode::TicksToRadians | ( | int | joint, | |
unsigned char | ticks | |||
) | [inline] |
ros::Publisher P2OSNode::aio_pub_ [protected] |
int P2OSNode::bumpstall [protected] |
ros::Subscriber P2OSNode::cmdmstate_sub_ [protected] |
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] |
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] |
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] |