Public Slots | Signals | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
Ros Class Reference

#include <Ros.h>

List of all members.

Public Slots

void currentCameraTabChanged (int index)
bool decrease_speed ()
bool increase_backward_speed ()
bool increase_speed ()
bool motor_stop ()
void moveElbowArm (double elbow)
void moveGripper (bool state)
void moveShoulderArm (double shoulder)
void Pan_control (int value)
void ResetArm ()
void rotateArm (double angle)
void setSpeedFast (bool toggled)
void setSpeedModerate (bool toggled)
void setSpeedSlow (bool toggled)
bool stop_turn ()
void Tilt_control (int value)
bool turn_left ()
bool turn_right ()
void turnWrist (float angle)

Signals

void angleWristReal (double angle)
void arm_model (bool arm_al5a, bool arm_pincher, bool arm_reactor, bool arm_old_corobot)
void battery_percent (int value)
void battery_volts (double volts)
void bumper_update (int bumper1, int bumper2, int bumper3, int bumper4)
void gps_coord (double lat, double lon)
void gps_lat (double lat)
void gps_lon (double lon)
void hokuyo_update (Hokuyo_Points *hokuyo_points)
void imu_data (double acc_x, double acc_y, double acc_z, double ang_x, double ang_y, double ang_z)
void irData (double ir01, double ir02)
void magnetic_data (double mag_x, double mag_y, double mag_z)
void posArmReal (double x, double y)
void save_image (bool save)
void update_kinectDepthcam (QImage image)
void update_kinectRGBcam (QImage image)
void update_mapimage (QImage image)
void update_ptzcam (QImage image)
void update_rearcam (QImage image)
void velocity_info (double linear, double angular)

Public Member Functions

void bumperCallback (const corobot_msgs::SensorMsg::ConstPtr &msg)
void closeGripper ()
void gpsCallback (const sensor_msgs::NavSatFix::ConstPtr &msg)
void imuCallback (const sensor_msgs::Imu::ConstPtr &msg)
void init (int argc, char *argv[])
void init (int argc, char *argv[], const std::string &master, const std::string &host)
void irCallback (const corobot_msgs::SensorMsg::ConstPtr &msg)
void kinectdepthCallback (const sensor_msgs::Image::ConstPtr &msg)
void kinectrgbCallback (const sensor_msgs::CompressedImage::ConstPtr &msg)
void magCallback (const sensor_msgs::MagneticField::ConstPtr &msg)
void mapCallback (const sensor_msgs::CompressedImage::ConstPtr &msg)
void openGripper ()
void powerCallback (const corobot_msgs::PowerMsgConstPtr &msg)
void ptz_camCallback (const sensor_msgs::Image::ConstPtr &msg)
void ptz_camCallback_compressed (const sensor_msgs::CompressedImage::ConstPtr &msg)
void rear_camCallback (const sensor_msgs::Image::ConstPtr &msg)
void rear_camCallback_compressed (const sensor_msgs::CompressedImage::ConstPtr &msg)
void resetArm ()
bool resetOdom ()
 Ros ()
void run ()
void scanCallback (const sensor_msgs::LaserScan::ConstPtr &msg)
bool setOdom (float x, float y)
void subscribe ()
void takepicCallback (const corobot_msgs::takepic::ConstPtr &msg)
void velocityCallback (const nav_msgs::Odometry::ConstPtr &msg)
 ~Ros ()

Public Attributes

Hokuyo_Pointshokuyo_points_
int move_speed_level
int pan
ros::Publisher pan_tilt_control
int tilt
int turning_speed_level

Private Member Functions

void timerCallback (const ros::TimerEvent &event)

Private Attributes

ros::Subscriber arm
bool arm_al5a
bool arm_old_phidget
bool arm_old_ssc32
bool arm_pincher
float arm_px
float arm_py
bool arm_reactor
ros::Subscriber bumper
int bumper_data [4]
bool cameraFront_jpeg_compression
ros::Subscriber cameraImage
ros::Subscriber cameraInfo
bool cameraRear_jpeg_compression
bool Corobot
ros::Publisher driveControl_pub
ros::Subscriber gps
ros::Subscriber imu
bool initialized
ros::Subscriber ir
double ir01
double ir02
ros::Subscriber kinect_depth
ros::Subscriber kinect_rgb
bool kinect_selected
ros::Subscriber kinect_skel
ros::Subscriber magnetic
ros::Subscriber map_image
ros::Publisher moveArm_pub
ros::Subscriber phidget_info_sub
ros::Subscriber power
ros::Subscriber ptz
ros::Subscriber ptz_cam
ros::Subscriber rear_cam
ros::Subscriber scan
ros::ServiceClient setOdom_client
float speed_a
float speed_left
float speed_right
int speed_value
float speed_x
ros::Subscriber ssc32_info_sub
ros::Subscriber takepic_sub
ros::Timer timer
bool turningLeft
bool turningRight
ros::Subscriber velocity
ros::Publisher velocityValue_pub

Detailed Description

Definition at line 35 of file Ros.h.


Constructor & Destructor Documentation

Ros::~Ros ( )

Definition at line 77 of file Ros.cpp.

Ros::Ros ( )

Definition at line 43 of file Ros.cpp.


Member Function Documentation

void Ros::angleWristReal ( double  angle) [signal]
void Ros::arm_model ( bool  arm_al5a,
bool  arm_pincher,
bool  arm_reactor,
bool  arm_old_corobot 
) [signal]
void Ros::battery_percent ( int  value) [signal]
void Ros::battery_volts ( double  volts) [signal]
void Ros::bumper_update ( int  bumper1,
int  bumper2,
int  bumper3,
int  bumper4 
) [signal]
void Ros::bumperCallback ( const corobot_msgs::SensorMsg::ConstPtr &  msg)

Definition at line 313 of file Ros.cpp.

Definition at line 506 of file Ros.cpp.

void Ros::currentCameraTabChanged ( int  index) [slot]

Definition at line 149 of file Ros.cpp.

bool Ros::decrease_speed ( ) [slot]

Definition at line 534 of file Ros.cpp.

void Ros::gps_coord ( double  lat,
double  lon 
) [signal]
void Ros::gps_lat ( double  lat) [signal]
void Ros::gps_lon ( double  lon) [signal]
void Ros::gpsCallback ( const sensor_msgs::NavSatFix::ConstPtr &  msg)

Definition at line 379 of file Ros.cpp.

void Ros::hokuyo_update ( Hokuyo_Points hokuyo_points) [signal]
void Ros::imu_data ( double  acc_x,
double  acc_y,
double  acc_z,
double  ang_x,
double  ang_y,
double  ang_z 
) [signal]
void Ros::imuCallback ( const sensor_msgs::Imu::ConstPtr &  msg)

Definition at line 423 of file Ros.cpp.

Definition at line 596 of file Ros.cpp.

bool Ros::increase_speed ( ) [slot]

Definition at line 569 of file Ros.cpp.

void Ros::init ( int  argc,
char *  argv[] 
)

Definition at line 137 of file Ros.cpp.

void Ros::init ( int  argc,
char *  argv[],
const std::string &  master,
const std::string &  host 
)

Definition at line 199 of file Ros.cpp.

void Ros::irCallback ( const corobot_msgs::SensorMsg::ConstPtr &  msg)

Definition at line 291 of file Ros.cpp.

void Ros::irData ( double  ir01,
double  ir02 
) [signal]
void Ros::kinectdepthCallback ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 243 of file Ros.cpp.

void Ros::kinectrgbCallback ( const sensor_msgs::CompressedImage::ConstPtr &  msg)

Definition at line 268 of file Ros.cpp.

void Ros::magCallback ( const sensor_msgs::MagneticField::ConstPtr &  msg)

Definition at line 439 of file Ros.cpp.

void Ros::magnetic_data ( double  mag_x,
double  mag_y,
double  mag_z 
) [signal]
void Ros::mapCallback ( const sensor_msgs::CompressedImage::ConstPtr &  msg)

Definition at line 368 of file Ros.cpp.

bool Ros::motor_stop ( ) [slot]

Definition at line 741 of file Ros.cpp.

void Ros::moveElbowArm ( double  elbow) [slot]

Definition at line 773 of file Ros.cpp.

void Ros::moveGripper ( bool  state) [slot]

Definition at line 451 of file Ros.cpp.

void Ros::moveShoulderArm ( double  shoulder) [slot]

Definition at line 759 of file Ros.cpp.

void Ros::openGripper ( )

Definition at line 492 of file Ros.cpp.

void Ros::Pan_control ( int  value) [slot]

Definition at line 833 of file Ros.cpp.

void Ros::posArmReal ( double  x,
double  y 
) [signal]
void Ros::powerCallback ( const corobot_msgs::PowerMsgConstPtr &  msg)

Definition at line 302 of file Ros.cpp.

void Ros::ptz_camCallback ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 345 of file Ros.cpp.

void Ros::ptz_camCallback_compressed ( const sensor_msgs::CompressedImage::ConstPtr &  msg)

Definition at line 357 of file Ros.cpp.

void Ros::rear_camCallback ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 323 of file Ros.cpp.

void Ros::rear_camCallback_compressed ( const sensor_msgs::CompressedImage::ConstPtr &  msg)

Definition at line 334 of file Ros.cpp.

void Ros::ResetArm ( ) [slot]

Definition at line 801 of file Ros.cpp.

void Ros::resetArm ( )
bool Ros::resetOdom ( )
void Ros::rotateArm ( double  angle) [slot]

Definition at line 787 of file Ros.cpp.

void Ros::run ( )

Definition at line 144 of file Ros.cpp.

void Ros::save_image ( bool  save) [signal]
void Ros::scanCallback ( const sensor_msgs::LaserScan::ConstPtr &  msg)

Definition at line 389 of file Ros.cpp.

bool Ros::setOdom ( float  x,
float  y 
)
void Ros::setSpeedFast ( bool  toggled) [slot]

Definition at line 210 of file Ros.cpp.

void Ros::setSpeedModerate ( bool  toggled) [slot]

Definition at line 221 of file Ros.cpp.

void Ros::setSpeedSlow ( bool  toggled) [slot]

Definition at line 232 of file Ros.cpp.

bool Ros::stop_turn ( ) [slot]

Definition at line 704 of file Ros.cpp.

void Ros::subscribe ( )

Definition at line 84 of file Ros.cpp.

void Ros::takepicCallback ( const corobot_msgs::takepic::ConstPtr &  msg)

Definition at line 414 of file Ros.cpp.

void Ros::Tilt_control ( int  value) [slot]

Definition at line 843 of file Ros.cpp.

void Ros::timerCallback ( const ros::TimerEvent event) [private]

Definition at line 520 of file Ros.cpp.

bool Ros::turn_left ( ) [slot]

Definition at line 622 of file Ros.cpp.

bool Ros::turn_right ( ) [slot]

Definition at line 664 of file Ros.cpp.

void Ros::turnWrist ( float  angle) [slot]

Definition at line 459 of file Ros.cpp.

void Ros::update_kinectDepthcam ( QImage  image) [signal]
void Ros::update_kinectRGBcam ( QImage  image) [signal]
void Ros::update_mapimage ( QImage  image) [signal]
void Ros::update_ptzcam ( QImage  image) [signal]
void Ros::update_rearcam ( QImage  image) [signal]
void Ros::velocity_info ( double  linear,
double  angular 
) [signal]
void Ros::velocityCallback ( const nav_msgs::Odometry::ConstPtr &  msg)

Definition at line 282 of file Ros.cpp.


Member Data Documentation

Definition at line 46 of file Ros.h.

bool Ros::arm_al5a [private]

Definition at line 63 of file Ros.h.

bool Ros::arm_old_phidget [private]

Definition at line 63 of file Ros.h.

bool Ros::arm_old_ssc32 [private]

Definition at line 63 of file Ros.h.

bool Ros::arm_pincher [private]

Definition at line 63 of file Ros.h.

float Ros::arm_px [private]

Definition at line 68 of file Ros.h.

float Ros::arm_py [private]

Definition at line 68 of file Ros.h.

bool Ros::arm_reactor [private]

Definition at line 63 of file Ros.h.

Definition at line 46 of file Ros.h.

int Ros::bumper_data[4] [private]

Definition at line 72 of file Ros.h.

Definition at line 62 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 62 of file Ros.h.

bool Ros::Corobot [private]

Definition at line 78 of file Ros.h.

Definition at line 51 of file Ros.h.

Definition at line 47 of file Ros.h.

Definition at line 172 of file Ros.h.

Definition at line 46 of file Ros.h.

bool Ros::initialized [private]

Definition at line 67 of file Ros.h.

Definition at line 46 of file Ros.h.

double Ros::ir01 [private]

Definition at line 71 of file Ros.h.

double Ros::ir02 [private]

Definition at line 71 of file Ros.h.

Definition at line 47 of file Ros.h.

Definition at line 47 of file Ros.h.

bool Ros::kinect_selected [private]

Definition at line 75 of file Ros.h.

Definition at line 47 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 169 of file Ros.h.

Definition at line 51 of file Ros.h.

int Ros::pan

Definition at line 167 of file Ros.h.

Definition at line 136 of file Ros.h.

Definition at line 54 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 48 of file Ros.h.

Definition at line 48 of file Ros.h.

Definition at line 47 of file Ros.h.

Definition at line 41 of file Ros.h.

float Ros::speed_a [private]

Definition at line 65 of file Ros.h.

float Ros::speed_left [private]

Definition at line 69 of file Ros.h.

float Ros::speed_right [private]

Definition at line 69 of file Ros.h.

int Ros::speed_value [private]

Definition at line 66 of file Ros.h.

float Ros::speed_x [private]

Definition at line 65 of file Ros.h.

Definition at line 54 of file Ros.h.

Definition at line 58 of file Ros.h.

int Ros::tilt

Definition at line 167 of file Ros.h.

Definition at line 44 of file Ros.h.

Definition at line 170 of file Ros.h.

bool Ros::turningLeft [private]

Definition at line 70 of file Ros.h.

bool Ros::turningRight [private]

Definition at line 70 of file Ros.h.

Definition at line 46 of file Ros.h.

Definition at line 51 of file Ros.h.


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


corobot_teleop
Author(s):
autogenerated on Wed Aug 26 2015 11:09:59