#include <p2os.hpp>
Definition at line 83 of file p2os.hpp.
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.
void P2OSNode::check_and_set_gripper_state |
( |
| ) |
|
void P2OSNode::check_and_set_motor_state |
( |
| ) |
|
void P2OSNode::check_and_set_vel |
( |
| ) |
|
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 |
convert degrees to ticks
Definition at line 844 of file p2os.cpp.
double P2OSNode::get_pulse |
( |
| ) |
|
|
inline |
void P2OSNode::gripperCallback |
( |
const p2os_msgs::GripperStateConstPtr & |
msg | ) |
|
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 |
( |
| ) |
|
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 |
| ) |
|
int P2OSNode::SendReceive |
( |
P2OSPacket * |
pkt, |
|
|
bool |
publish_data = true |
|
) |
| |
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 | ) |
|
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
-
val | Determines what state the motor should be. 1 = enabled, 0 = disabled. |
Definition at line 805 of file p2os.cpp.
void P2OSNode::ToggleSonarPower |
( |
unsigned char |
val | ) |
|
void P2OSNode::updateDiagnostics |
( |
| ) |
|
std::string P2OSNode::base_link_frame_id |
|
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.
geometry_msgs::Twist P2OSNode::cmdvel_ |
Command Velocity subscriber.
Definition at line 196 of file p2os.hpp.
double P2OSNode::desired_freq |
|
protected |
int P2OSNode::direct_wheel_vel_control |
|
protected |
Control wheel velocities individually?
Definition at line 169 of file p2os.hpp.
bool P2OSNode::gripper_dirty_ = false |
|
protected |
p2os_msgs::GripperState P2OSNode::gripper_state_ |
Gripper state publisher.
Definition at line 200 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 |
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.
Node Handler used for publication of data.
Definition at line 135 of file p2os.hpp.
Node Handler used for private data publication.
Definition at line 137 of file p2os.hpp.
std::string P2OSNode::odom_frame_id |
|
protected |
sensor data container
Definition at line 202 of file p2os.hpp.
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 |
int P2OSNode::radio_modemp |
|
protected |
bool P2OSNode::use_sonar_ |
|
protected |
Use the sonar array?
Definition at line 190 of file p2os.hpp.
The documentation for this class was generated from the following files: