Public Slots | 
| void  | corobot (bool value) | 
| 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  | ResetArm () | 
| void  | rotateArm (double angle) | 
| void  | select_kinect (bool value) | 
| void  | setSpeedFast (bool toggled) | 
| void  | setSpeedModerate (bool toggled) | 
| void  | setSpeedSlow (bool toggled) | 
| bool  | stop_turn () | 
| 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  | griperState (int state) | 
| void  | hokuyo_update (Hokuyo_Points *hokuyo_points) | 
| void  | irData (double ir01, double ir02) | 
| void  | posArmReal (double x, double y) | 
| void  | spatial_data (double acc_x, double acc_y, double acc_z, double ang_x, double ang_y, double ang_z, double mag_x, double mag_y, double mag_z) | 
| 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  | add_allcam_scene (QGraphicsScene *scene) | 
| void  | add_camera_info_scene (QGraphicsScene *scene) | 
| void  | add_front_image_scene (QGraphicsScene *scene) | 
| void  | add_kinect_depth_scene (QGraphicsScene *scene) | 
| void  | add_kinect_rgb_scene (QGraphicsScene *scene) | 
| void  | add_map_image_scene (QGraphicsScene *scene) | 
| void  | add_ptz_cam_scene (QGraphicsScene *scene) | 
| void  | add_rear_cam_scene (QGraphicsScene *scene) | 
| void  | bumperCallback (const corobot_msgs::BumperMsg::ConstPtr &msg) | 
| void  | cameraImageCallback (const sensor_msgs::Image::ConstPtr &msg) | 
| void  | cameraInfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg) | 
| void  | closeGripper () | 
| void  | gpsCallback (const sensor_msgs::NavSatFix::ConstPtr &msg) | 
| void  | gripperCallback (const corobot_msgs::GripperMsg::ConstPtr &msg) | 
| void  | init () | 
| void  | init (const std::string &master, const std::string &host) | 
| void  | irCallback (const corobot_msgs::IrMsg::ConstPtr &msg) | 
| void  | kinectdepthCallback (const sensor_msgs::Image::ConstPtr &msg) | 
| void  | kinectrgbCallback (const sensor_msgs::CompressedImage::ConstPtr &msg) | 
| void  | mapCallback (const sensor_msgs::CompressedImage::ConstPtr &msg) | 
| void  | openGripper () | 
| void  | phidgetinfoCallback (const corobot_msgs::phidget_info::ConstPtr &msg) | 
| 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  | setCameraControl (int id, int value) | 
| bool  | setCameraMode (int width, int weight, bool immediately, int fps, bool auto_exposure) | 
| bool  | setCameraState (bool state) | 
| bool  | setOdom (float x, float y) | 
| bool  | setPtzcommand (int pan, int tilt) | 
| bool  | setPtzmode (int mode) | 
| void  | spatialCallback (const corobot_msgs::spatial::ConstPtr &msg) | 
| void  | ssc32infoCallback (const corobot_msgs::ssc32_info::ConstPtr &msg) | 
| void  | subscribe () | 
| void  | takepicCallback (const corobot_msgs::takepic::ConstPtr &msg) | 
| void  | velocityCallback (const nav_msgs::Odometry::ConstPtr &msg) | 
|   | ~Ros () | 
Public Attributes | 
| int  | backwardspeed [3] | 
| int  | forwardspeed [3] | 
| int  | forwardspeed_chosen | 
| Hokuyo_Points *  | hokuyo_points_ | 
| int  | left_motor_value | 
| int  | move_speed_level | 
| int  | pan | 
| ros::Publisher  | pan_tilt_control | 
| int  | right_motor_value | 
| int  | tilt | 
| int  | turning_speed_level | 
| int  | turnleftspeed | 
| int  | turnrightspeed | 
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 | 
| 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  | gripper | 
| Image  | image_camera | 
| Image  | image_front_cam | 
| Image  | image_kinect_depth | 
| Image  | image_kinect_rgb | 
| Image  | image_map_image | 
| Image  | image_ptz_cam | 
| Image  | image_rear_cam | 
| bool  | initialized | 
| ros::Subscriber  | ir | 
| ros::Subscriber  | kinect_depth | 
| ros::Subscriber  | kinect_rgb | 
| bool  | kinect_selected | 
| ros::Subscriber  | kinect_skel | 
| 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 | 
| QGraphicsScene *  | scenes | 
| QGraphicsScene *  | scenes_front_image | 
| QGraphicsScene *  | scenes_kinect_depth | 
| QGraphicsScene *  | scenes_kinect_rgb | 
| QGraphicsScene *  | scenes_map_image | 
| QGraphicsScene *  | scenes_ptz_cam | 
| QGraphicsScene *  | scenes_rear_cam | 
| ros::ServiceClient  | setOdom_client | 
| ros::Subscriber  | spatial | 
| 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 | 
Definition at line 48 of file Ros.h.