Public Member Functions | Public Attributes | Protected Attributes | List of all members
P2OSNode Class Reference

#include <p2os.hpp>

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 More...
 
double get_pulse ()
 
void gripperCallback (const p2os_msgs::GripperStateConstPtr &msg)
 
 P2OSNode (ros::NodeHandle n)
 P2OS robot driver node. More...
 
unsigned char RadiansToTicks (int joint, double rads)
 Convert radians to ticks. More...
 
double RadsPerSectoSecsPerTick (int joint, double speed)
 Convert radians per second to radians per encoder tick. More...
 
void ResetRawPositions ()
 
double SecsPerTicktoRadsPerSec (int joint, double secs)
 Convert Seconds per encoder tick to radians per second. More...
 
void SendPulse (void)
 
int SendReceive (P2OSPacket *pkt, bool publish_data=true)
 
int Setup ()
 Setup the robot for use. Communicates with the robot directly. More...
 
int Shutdown ()
 Prepare for shutdown. More...
 
void StandardSIPPutData (ros::Time ts)
 
double TicksToDegrees (int joint, unsigned char ticks)
 Convert ticks to degrees. More...
 
double TicksToRadians (int joint, unsigned char ticks)
 Convert ticks to radians. More...
 
void ToggleMotorPower (unsigned char val)
 Toggle motors on/off. More...
 
void ToggleSonarPower (unsigned char val)
 
void updateDiagnostics ()
 
virtual ~P2OSNode ()
 

Public Attributes

p2os_msgs::MotorState cmdmotor_state_
 Motor state publisher. More...
 
geometry_msgs::Twist cmdvel_
 Command Velocity subscriber. More...
 
p2os_msgs::GripperState gripper_state_
 Gripper state publisher. More...
 
ros_p2os_data_t p2os_data
 sensor data container More...
 

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? More...
 
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? More...
 
ros::Publisher grip_state_pub_
 
bool gripper_dirty_ = false
 
ros::Subscriber gripper_sub_
 
int joystick
 Use Joystick? More...
 
double lastPulseTime
 Last time the node received or sent a pulse. More...
 
bool motor_dirty
 
int16_t motor_max_rot_accel
 Maximum rotational acceleration in radians per second per second. More...
 
int16_t motor_max_rot_decel
 Minimum rotational acceleration in Meters per second per second. More...
 
int motor_max_speed
 Maximum motor speed in Meters per second. More...
 
int16_t motor_max_trans_accel
 Maximum translational acceleration in Meters per second per second. More...
 
int16_t motor_max_trans_decel
 Minimum translational acceleration in Meters per second per second. More...
 
int motor_max_turnspeed
 Maximum turn speed in radians per second. More...
 
ros::Publisher mstate_pub_
 
ros::NodeHandle n
 Node Handler used for publication of data. More...
 
ros::NodeHandle nh_private
 Node Handler used for private data publication. More...
 
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. More...
 
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_
 Use the sonar array? More...
 
bool vel_dirty
 
ros::Time veltime
 

Detailed Description

Definition at line 83 of file p2os.hpp.

Constructor & Destructor Documentation

P2OSNode::P2OSNode ( ros::NodeHandle  n)
explicit

P2OS robot driver node.

This class contains, essentially, the main means of communication between the robot and ROS.

Constructor for P2OS node.

This brings up the P2OS system for ROS operation.

Definition at line 31 of file p2os.cpp.

P2OSNode::~P2OSNode ( )
virtual

Destructor

Definition at line 131 of file p2os.cpp.

Member Function Documentation

void P2OSNode::check_and_set_gripper_state ( )

Definition at line 160 of file p2os.cpp.

void P2OSNode::check_and_set_motor_state ( )

Definition at line 139 of file p2os.cpp.

void P2OSNode::check_and_set_vel ( )

Definition at line 215 of file p2os.cpp.

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

Definition at line 757 of file p2os.cpp.

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

Definition at line 745 of file p2os.cpp.

void P2OSNode::cmdmotor_state ( const p2os_msgs::MotorStateConstPtr &  msg)

Definition at line 133 of file p2os.cpp.

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

Definition at line 193 of file p2os.cpp.

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

convert degrees to ticks

Definition at line 844 of file p2os.cpp.

double P2OSNode::get_pulse ( )
inline

Definition at line 127 of file p2os.hpp.

void P2OSNode::gripperCallback ( const p2os_msgs::GripperStateConstPtr &  msg)

Definition at line 265 of file p2os.cpp.

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

Convert radians to ticks.

Definition at line 874 of file p2os.cpp.

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

Convert radians per second to radians per encoder tick.

Definition at line 881 of file p2os.cpp.

void P2OSNode::ResetRawPositions ( )

Definition at line 768 of file p2os.cpp.

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

Convert Seconds per encoder tick to radians per second.

Definition at line 897 of file p2os.cpp.

void P2OSNode::SendPulse ( void  )

Definition at line 907 of file p2os.cpp.

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

Definition at line 688 of file p2os.cpp.

int P2OSNode::Setup ( )

Setup the robot for use. Communicates with the robot directly.

Definition at line 271 of file p2os.cpp.

int P2OSNode::Shutdown ( )

Prepare for shutdown.

Definition at line 623 of file p2os.cpp.

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

Definition at line 659 of file p2os.cpp.

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

Convert ticks to degrees.

Definition at line 825 of file p2os.cpp.

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

Convert ticks to radians.

Definition at line 867 of file p2os.cpp.

void P2OSNode::ToggleMotorPower ( unsigned char  val)

Toggle motors on/off.

Turn on/off the robots in accordance to val.

Parameters
valDetermines what state the motor should be. 1 = enabled, 0 = disabled.

Definition at line 805 of file p2os.cpp.

void P2OSNode::ToggleSonarPower ( unsigned char  val)

Definition at line 787 of file p2os.cpp.

void P2OSNode::updateDiagnostics ( )

Definition at line 740 of file p2os.cpp.

Member Data Documentation

ros::Publisher P2OSNode::aio_pub_
protected

Definition at line 142 of file p2os.hpp.

std::string P2OSNode::base_link_frame_id
protected

Definition at line 154 of file p2os.hpp.

diagnostic_updater::DiagnosedPublisher<p2os_msgs::BatteryState> P2OSNode::batt_pub_
protected

Definition at line 141 of file p2os.hpp.

int P2OSNode::bumpstall
protected

Stall I hit a wall?

Definition at line 165 of file p2os.hpp.

p2os_msgs::MotorState P2OSNode::cmdmotor_state_

Motor state publisher.

Definition at line 198 of file p2os.hpp.

ros::Subscriber P2OSNode::cmdmstate_sub_
protected

Definition at line 145 of file p2os.hpp.

geometry_msgs::Twist P2OSNode::cmdvel_

Command Velocity subscriber.

Definition at line 196 of file p2os.hpp.

ros::Subscriber P2OSNode::cmdvel_sub_
protected

Definition at line 145 of file p2os.hpp.

double P2OSNode::desired_freq
protected

Definition at line 186 of file p2os.hpp.

diagnostic_updater::Updater P2OSNode::diagnostic_
protected

Definition at line 139 of file p2os.hpp.

ros::Publisher P2OSNode::dio_pub_
protected

Definition at line 142 of file p2os.hpp.

int P2OSNode::direct_wheel_vel_control
protected

Control wheel velocities individually?

Definition at line 169 of file p2os.hpp.

ros::Publisher P2OSNode::grip_state_pub_
protected

Definition at line 142 of file p2os.hpp.

bool P2OSNode::gripper_dirty_ = false
protected

Definition at line 159 of file p2os.hpp.

p2os_msgs::GripperState P2OSNode::gripper_state_

Gripper state publisher.

Definition at line 200 of file p2os.hpp.

ros::Subscriber P2OSNode::gripper_sub_
protected

Definition at line 145 of file p2os.hpp.

int P2OSNode::joystick
protected

Use Joystick?

Definition at line 167 of file p2os.hpp.

double P2OSNode::lastPulseTime
protected

Last time the node received or sent a pulse.

Definition at line 188 of file p2os.hpp.

bool P2OSNode::motor_dirty
protected

Definition at line 158 of file p2os.hpp.

int16_t P2OSNode::motor_max_rot_accel
protected

Maximum rotational acceleration in radians per second per second.

Definition at line 181 of file p2os.hpp.

int16_t P2OSNode::motor_max_rot_decel
protected

Minimum rotational acceleration in Meters per second per second.

Definition at line 183 of file p2os.hpp.

int P2OSNode::motor_max_speed
protected

Maximum motor speed in Meters per second.

Definition at line 173 of file p2os.hpp.

int16_t P2OSNode::motor_max_trans_accel
protected

Maximum translational acceleration in Meters per second per second.

Definition at line 177 of file p2os.hpp.

int16_t P2OSNode::motor_max_trans_decel
protected

Minimum translational acceleration in Meters per second per second.

Definition at line 179 of file p2os.hpp.

int P2OSNode::motor_max_turnspeed
protected

Maximum turn speed in radians per second.

Definition at line 175 of file p2os.hpp.

ros::Publisher P2OSNode::mstate_pub_
protected

Definition at line 142 of file p2os.hpp.

ros::NodeHandle P2OSNode::n
protected

Node Handler used for publication of data.

Definition at line 135 of file p2os.hpp.

ros::NodeHandle P2OSNode::nh_private
protected

Node Handler used for private data publication.

Definition at line 137 of file p2os.hpp.

tf::TransformBroadcaster P2OSNode::odom_broadcaster
protected

Definition at line 147 of file p2os.hpp.

std::string P2OSNode::odom_frame_id
protected

Definition at line 153 of file p2os.hpp.

ros_p2os_data_t P2OSNode::p2os_data

sensor data container

Definition at line 202 of file p2os.hpp.

int P2OSNode::param_idx
protected

Definition at line 160 of file p2os.hpp.

ros::Publisher P2OSNode::pose_pub_
protected

Definition at line 144 of file p2os.hpp.

int P2OSNode::psos_fd
protected

Definition at line 155 of file p2os.hpp.

std::string P2OSNode::psos_serial_port
protected

Definition at line 151 of file p2os.hpp.

std::string P2OSNode::psos_tcp_host
protected

Definition at line 152 of file p2os.hpp.

int P2OSNode::psos_tcp_port
protected

Definition at line 157 of file p2os.hpp.

bool P2OSNode::psos_use_tcp
protected

Definition at line 156 of file p2os.hpp.

P2OSPtz P2OSNode::ptz_
protected

Definition at line 192 of file p2os.hpp.

ros::Subscriber P2OSNode::ptz_cmd_sub_
protected

Definition at line 145 of file p2os.hpp.

ros::Publisher P2OSNode::ptz_state_pub_
protected

Definition at line 142 of file p2os.hpp.

double P2OSNode::pulse
protected

Pulse time.

Definition at line 185 of file p2os.hpp.

int P2OSNode::radio_modemp
protected

Definition at line 170 of file p2os.hpp.

int P2OSNode::rot_ki
protected

Definition at line 162 of file p2os.hpp.

int P2OSNode::rot_kp
protected

Definition at line 162 of file p2os.hpp.

int P2OSNode::rot_kv
protected

Definition at line 162 of file p2os.hpp.

SIP* P2OSNode::sippacket
protected

Definition at line 150 of file p2os.hpp.

ros::Publisher P2OSNode::sonar_pub_
protected

Definition at line 142 of file p2os.hpp.

int P2OSNode::trans_ki
protected

Definition at line 162 of file p2os.hpp.

int P2OSNode::trans_kp
protected

Definition at line 162 of file p2os.hpp.

int P2OSNode::trans_kv
protected

Definition at line 162 of file p2os.hpp.

bool P2OSNode::use_sonar_
protected

Use the sonar array?

Definition at line 190 of file p2os.hpp.

bool P2OSNode::vel_dirty
protected

Definition at line 158 of file p2os.hpp.

ros::Time P2OSNode::veltime
protected

Definition at line 148 of file p2os.hpp.


The documentation for this class was generated from the following files:


p2os_driver
Author(s): Hunter L. Allen , David Feil-Seifer , Aris Synodinos , Brian Gerkey, Kasper Stoy, Richard Vaughan, Andrew Howard, Tucker Hermans, ActivMedia Robotics LLC, MobileRobots Inc.
autogenerated on Sat Jun 20 2020 03:29:42