Public Member Functions | Public Attributes | Private Attributes
OmnixNode Class Reference

#include <omnix.h>

List of all members.

Public Member Functions

void closeOmnixSocket ()
void cmdvelCallback (const geometry_msgs::Twist::ConstPtr &cmd_vel)
bool DisableJoystickCallback (omnix::DisableJoystick::Request &req, omnix::DisableJoystick::Response &res)
bool EnableJoystickCallback (omnix::EnableJoystick::Request &req, omnix::EnableJoystickResponse &res)
bool EngageBrakeCallback (omnix::EngageBrake::Request &req, omnix::EngageBrake::Response &res)
void initCommands ()
void joyCallback (const sensor_msgs::Joy::ConstPtr &joy)
 OmnixNode ()
void openOmnixSocket ()
void openOmnixSocketRec ()
bool peekForNewline ()
void readTimerCallback (const ros::TimerEvent &e)
bool recvResponse (bool blocking=true)
bool ReleaseBrakeCallback (omnix::ReleaseBrake::Request &req, omnix::ReleaseBrake::Response &res)
bool sendCommand (const std::string &cmd)
void sendGetJointPosition ()
void timerCallback (const ros::TimerEvent &e)
 ~OmnixNode ()

Public Attributes

ros::Subscriber cmd_vel_sub_
ros::Duration estop_timeout_
ros::Timer estop_timer_
ros::Subscriber joy_sub_
ros::NodeHandle n_
ros::Publisher odom_pub_
ros::Timer read_timer_
tf::TransformBroadcaster tf_
ros::Publisher wheel_pos_pub_

Private Attributes

bool brake_engaged
int counter
ros::ServiceServer disable_joystick_service_
std::string DisableJoystickCommand
std::string DisableRobotControlCommand
ros::ServiceServer disengage_brake_service_
bool emergency_stop
std::string EnableJoystickCommand
std::string EnableRobotControlCommand
ros::ServiceServer engage_brake_service_
std::string EngageBrakeCommand
bool first_write
ros::ServiceServer get_joint_position_service_
std::string GetJointPositionCommand
struct hostent * host
struct hostent * host_rec
std::string hostname
bool joystick_controlled
ros::Time last_estop_recd
geometry_msgs::Twist * last_vel_cmd
ros::Time last_vel_cmd_recd
ros::Time last_vel_cmd_sent
double odom_x
double odom_y
double odom_yaw
bool open_rec_socket
int portno
int portno_rec
double prev_j1
double prev_j2
double prev_j3
double prev_j4
ros::Time prev_time
char rec_buf [1024]
int rec_buf_size
bool recv_odom
std::string ReleaseBrakeCommand
struct sockaddr_in server_addr
int server_addr_len
struct sockaddr_in server_addr_rec
int server_addr_rec_len
struct sockaddr_in server_addr_rec_other
int server_addr_rec_other_len
std::string SetBlinkPatternCommand
std::string SetJointVelocitiesCommand
std::string SetVelocityCommand
int sock
int sock_rec
bool verbose
double vt
double vx
double vy

Detailed Description

Definition at line 23 of file omnix.h.


Constructor & Destructor Documentation

Definition at line 4 of file omnix.cpp.

Definition at line 61 of file omnix.cpp.


Member Function Documentation

Definition at line 121 of file omnix.cpp.

void OmnixNode::cmdvelCallback ( const geometry_msgs::Twist::ConstPtr &  cmd_vel)

Definition at line 456 of file omnix.cpp.

bool OmnixNode::DisableJoystickCallback ( omnix::DisableJoystick::Request &  req,
omnix::DisableJoystick::Response &  res 
)

Definition at line 526 of file omnix.cpp.

bool OmnixNode::EnableJoystickCallback ( omnix::EnableJoystick::Request &  req,
omnix::EnableJoystickResponse &  res 
)

Definition at line 540 of file omnix.cpp.

bool OmnixNode::EngageBrakeCallback ( omnix::EngageBrake::Request &  req,
omnix::EngageBrake::Response &  res 
)

Definition at line 501 of file omnix.cpp.

void OmnixNode::initCommands ( ) [inline]

Definition at line 110 of file omnix.h.

void OmnixNode::joyCallback ( const sensor_msgs::Joy::ConstPtr &  joy)

Definition at line 127 of file omnix.cpp.

Definition at line 66 of file omnix.cpp.

Definition at line 90 of file omnix.cpp.

Definition at line 213 of file omnix.cpp.

Definition at line 135 of file omnix.cpp.

bool OmnixNode::recvResponse ( bool  blocking = true)

Definition at line 234 of file omnix.cpp.

bool OmnixNode::ReleaseBrakeCallback ( omnix::ReleaseBrake::Request &  req,
omnix::ReleaseBrake::Response &  res 
)

Definition at line 510 of file omnix.cpp.

bool OmnixNode::sendCommand ( const std::string &  cmd)

Definition at line 197 of file omnix.cpp.

Definition at line 382 of file omnix.cpp.

Definition at line 140 of file omnix.cpp.


Member Data Documentation

Definition at line 55 of file omnix.h.

Definition at line 84 of file omnix.h.

int OmnixNode::counter [private]

Definition at line 51 of file omnix.h.

Definition at line 34 of file omnix.h.

std::string OmnixNode::DisableJoystickCommand [private]

Definition at line 70 of file omnix.h.

Definition at line 73 of file omnix.h.

Definition at line 32 of file omnix.h.

Definition at line 53 of file omnix.h.

std::string OmnixNode::EnableJoystickCommand [private]

Definition at line 71 of file omnix.h.

std::string OmnixNode::EnableRobotControlCommand [private]

Definition at line 72 of file omnix.h.

Definition at line 31 of file omnix.h.

std::string OmnixNode::EngageBrakeCommand [private]

Definition at line 77 of file omnix.h.

Definition at line 88 of file omnix.h.

Definition at line 86 of file omnix.h.

Definition at line 54 of file omnix.h.

Definition at line 33 of file omnix.h.

std::string OmnixNode::GetJointPositionCommand [private]

Definition at line 76 of file omnix.h.

struct hostent* OmnixNode::host [private]

Definition at line 39 of file omnix.h.

struct hostent* OmnixNode::host_rec [private]

Definition at line 45 of file omnix.h.

std::string OmnixNode::hostname [private]

Definition at line 36 of file omnix.h.

Definition at line 85 of file omnix.h.

Definition at line 56 of file omnix.h.

Definition at line 27 of file omnix.h.

geometry_msgs::Twist* OmnixNode::last_vel_cmd [private]

Definition at line 29 of file omnix.h.

Definition at line 25 of file omnix.h.

Definition at line 26 of file omnix.h.

Definition at line 82 of file omnix.h.

Definition at line 89 of file omnix.h.

double OmnixNode::odom_x [private]

Definition at line 64 of file omnix.h.

double OmnixNode::odom_y [private]

Definition at line 64 of file omnix.h.

double OmnixNode::odom_yaw [private]

Definition at line 64 of file omnix.h.

Definition at line 59 of file omnix.h.

int OmnixNode::portno [private]

Definition at line 37 of file omnix.h.

int OmnixNode::portno_rec [private]

Definition at line 43 of file omnix.h.

double OmnixNode::prev_j1 [private]

Definition at line 65 of file omnix.h.

double OmnixNode::prev_j2 [private]

Definition at line 65 of file omnix.h.

double OmnixNode::prev_j3 [private]

Definition at line 65 of file omnix.h.

double OmnixNode::prev_j4 [private]

Definition at line 65 of file omnix.h.

Definition at line 67 of file omnix.h.

Definition at line 87 of file omnix.h.

char OmnixNode::rec_buf[1024] [private]

Definition at line 60 of file omnix.h.

int OmnixNode::rec_buf_size [private]

Definition at line 61 of file omnix.h.

Definition at line 57 of file omnix.h.

std::string OmnixNode::ReleaseBrakeCommand [private]

Definition at line 78 of file omnix.h.

struct sockaddr_in OmnixNode::server_addr [private]

Definition at line 40 of file omnix.h.

Definition at line 41 of file omnix.h.

struct sockaddr_in OmnixNode::server_addr_rec [private]

Definition at line 46 of file omnix.h.

Definition at line 47 of file omnix.h.

struct sockaddr_in OmnixNode::server_addr_rec_other [private]

Definition at line 48 of file omnix.h.

Definition at line 49 of file omnix.h.

std::string OmnixNode::SetBlinkPatternCommand [private]

Definition at line 79 of file omnix.h.

std::string OmnixNode::SetJointVelocitiesCommand [private]

Definition at line 75 of file omnix.h.

std::string OmnixNode::SetVelocityCommand [private]

Definition at line 74 of file omnix.h.

int OmnixNode::sock [private]

Definition at line 38 of file omnix.h.

int OmnixNode::sock_rec [private]

Definition at line 44 of file omnix.h.

Definition at line 83 of file omnix.h.

Definition at line 58 of file omnix.h.

double OmnixNode::vt [private]

Definition at line 66 of file omnix.h.

double OmnixNode::vx [private]

Definition at line 66 of file omnix.h.

double OmnixNode::vy [private]

Definition at line 66 of file omnix.h.

Definition at line 90 of file omnix.h.


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


omnix
Author(s): Alexander J Trevor
autogenerated on Wed Nov 27 2013 12:06:10