#include <RobotDriver.h>
| Public Member Functions | |
| bool | checkCollision (double relativePose[]) | 
| checks wheter an envisioned movement of the base would collide the robot considering base_scan, currently supports only movements in x and y without rotation | |
| bool | checkCollision (tf::Stamped< tf::Pose > target) | 
| bool | driveInMap (tf::Stamped< tf::Pose > targetPose, bool exitWhenStuck=false) | 
| bool | driveInMap (const double targetPose[], bool exitWhenStuck=false) | 
| Drive forward a specified distance based on odometry information. | |
| bool | driveInOdom (const double targetPose[], bool exitWhenStuck=false) | 
| void | driveToMatch (std::vector< tf::Stamped< tf::Pose > > targetPose, std::vector< std::string > frame_ids) | 
| void | getRobotPose (tf::Stamped< tf::Pose > &marker) | 
| void | moveBase (const double pose[], bool useNavigation=false) | 
| void | moveBaseP (double x, double y, double oz, double ow, bool useNavigation=false) | 
| void | scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan_in) | 
| Static Public Member Functions | |
| static RobotDriver * | getInstance () | 
| static void | moveBase4 (double x, double y, double oz, double ow, bool useNavigation=false) | 
| Private Member Functions | |
| void | QuaternionToEuler (const btQuaternion &TQuat, btVector3 &TEuler) | 
| RobotDriver () | |
| ROS node initialization. | |
| Private Attributes | |
| ros::Publisher | cmd_vel_pub_ | 
| We will be publishing to the "cmd_vel" topic to issue commands. | |
| tf::TransformListener | listener_ | 
| We will be listening to TF transforms as well. | |
| ros::NodeHandle | nh_ | 
| The node handle we'll be using. | |
| size_t | numScanPoints | 
| laser_geometry::LaserProjection * | projector_ | 
| boost::mutex | scan_mutex | 
| double | scanPoints [5000][2] | 
| ros::Subscriber | subScan_ | 
| We need laser scans avoiding obstacles. | |
| bool | weHaveScan | 
| Static Private Attributes | |
| static RobotDriver * | instance = 0 | 
Definition at line 48 of file RobotDriver.h.
| RobotDriver::RobotDriver | ( | ) |  [private] | 
ROS node initialization.
Definition at line 38 of file RobotDriver.cpp.
| bool RobotDriver::checkCollision | ( | double | relativePose[] | ) | 
checks wheter an envisioned movement of the base would collide the robot considering base_scan, currently supports only movements in x and y without rotation
Definition at line 74 of file RobotDriver.cpp.
| bool RobotDriver::checkCollision | ( | tf::Stamped< tf::Pose > | target | ) | 
Definition at line 100 of file RobotDriver.cpp.
| bool RobotDriver::driveInMap | ( | tf::Stamped< tf::Pose > | targetPose, | 
| bool | exitWhenStuck = false | ||
| ) | 
limit speed depening on already travelled distance (start slowly) and distance to goal (final approach slow)
Definition at line 148 of file RobotDriver.cpp.
| bool RobotDriver::driveInMap | ( | const double | targetPose[], | 
| bool | exitWhenStuck = false | ||
| ) | 
Drive forward a specified distance based on odometry information.
Definition at line 362 of file RobotDriver.cpp.
| bool RobotDriver::driveInOdom | ( | const double | targetPose[], | 
| bool | exitWhenStuck = false | ||
| ) | 
Definition at line 373 of file RobotDriver.cpp.
| void RobotDriver::driveToMatch | ( | std::vector< tf::Stamped< tf::Pose > > | targetPose, | 
| std::vector< std::string > | frame_ids | ||
| ) | 
Definition at line 481 of file RobotDriver.cpp.
| RobotDriver * RobotDriver::getInstance | ( | ) |  [static] | 
Definition at line 47 of file RobotDriver.cpp.
| void RobotDriver::getRobotPose | ( | tf::Stamped< tf::Pose > & | marker | ) | 
Definition at line 109 of file RobotDriver.cpp.
| void RobotDriver::moveBase | ( | const double | pose[], | 
| bool | useNavigation = false | ||
| ) | 
//arm->startTrajectory(arm->twoPointTrajectory(Poses::untuckPoseA, Poses::tuckPose));
Definition at line 415 of file RobotDriver.cpp.
| void RobotDriver::moveBase4 | ( | double | x, | 
| double | y, | ||
| double | oz, | ||
| double | ow, | ||
| bool | useNavigation = false | ||
| ) |  [static] | 
Definition at line 404 of file RobotDriver.cpp.
| void RobotDriver::moveBaseP | ( | double | x, | 
| double | y, | ||
| double | oz, | ||
| double | ow, | ||
| bool | useNavigation = false | ||
| ) | 
Definition at line 471 of file RobotDriver.cpp.
| void RobotDriver::QuaternionToEuler | ( | const btQuaternion & | TQuat, | 
| btVector3 & | TEuler | ||
| ) |  [private] | 
Definition at line 132 of file RobotDriver.cpp.
| void RobotDriver::scanCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_in | ) | 
Definition at line 54 of file RobotDriver.cpp.
| ros::Publisher RobotDriver::cmd_vel_pub_  [private] | 
We will be publishing to the "cmd_vel" topic to issue commands.
Definition at line 54 of file RobotDriver.h.
| RobotDriver * RobotDriver::instance = 0  [static, private] | 
Definition at line 68 of file RobotDriver.h.
| tf::TransformListener RobotDriver::listener_  [private] | 
We will be listening to TF transforms as well.
Definition at line 56 of file RobotDriver.h.
| ros::NodeHandle RobotDriver::nh_  [private] | 
The node handle we'll be using.
Definition at line 52 of file RobotDriver.h.
| size_t RobotDriver::numScanPoints  [private] | 
Definition at line 63 of file RobotDriver.h.
Definition at line 59 of file RobotDriver.h.
| boost::mutex RobotDriver::scan_mutex  [private] | 
Definition at line 60 of file RobotDriver.h.
| double RobotDriver::scanPoints[5000][2]  [private] | 
Definition at line 62 of file RobotDriver.h.
| ros::Subscriber RobotDriver::subScan_  [private] | 
We need laser scans avoiding obstacles.
Definition at line 58 of file RobotDriver.h.
| bool RobotDriver::weHaveScan  [private] | 
Definition at line 61 of file RobotDriver.h.