Public Member Functions | |
| TurtlebotFollower () | |
| The constructor for the follower. Constructor for the follower. | |
| ~TurtlebotFollower () | |
Private Member Functions | |
| void | cloudcb (const PointCloud::ConstPtr &cloud) |
| Callback for point clouds. Callback for point clouds. Uses PCL to find the centroid of the points in a box in the center of the point cloud. Publishes cmd_vel messages with the goal from the cloud. | |
| virtual void | onInit () |
| OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics. | |
| void | reconfigure (turtlebot_follower::FollowerConfig &config, uint32_t level) |
Private Attributes | |
| ros::Publisher | cmdpub_ |
| double | goal_z_ |
| double | max_x_ |
| double | max_y_ |
| double | max_z_ |
| double | min_x_ |
| double | min_y_ |
| dynamic_reconfigure::Server < turtlebot_follower::FollowerConfig > * | srv_ |
| ros::Subscriber | sub_ |
| double | x_scale_ |
| double | z_scale_ |
The turtlebot follower nodelet. Subscribes to point clouds from the kinect, processes them, and publishes command vel messages.
Definition at line 46 of file follower.cpp.
| turtlebot_follower::TurtlebotFollower::TurtlebotFollower | ( | ) | [inline] |
The constructor for the follower. Constructor for the follower.
Definition at line 53 of file follower.cpp.
| turtlebot_follower::TurtlebotFollower::~TurtlebotFollower | ( | ) | [inline] |
Definition at line 61 of file follower.cpp.
| void turtlebot_follower::TurtlebotFollower::cloudcb | ( | const PointCloud::ConstPtr & | cloud | ) | [inline, private] |
Callback for point clouds. Callback for point clouds. Uses PCL to find the centroid of the points in a box in the center of the point cloud. Publishes cmd_vel messages with the goal from the cloud.
| cloud | The point cloud message. |
Definition at line 126 of file follower.cpp.
| virtual void turtlebot_follower::TurtlebotFollower::onInit | ( | ) | [inline, private, virtual] |
OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics.
Definition at line 85 of file follower.cpp.
| void turtlebot_follower::TurtlebotFollower::reconfigure | ( | turtlebot_follower::FollowerConfig & | config, | |
| uint32_t | level | |||
| ) | [inline, private] |
Definition at line 107 of file follower.cpp.
ros::Publisher turtlebot_follower::TurtlebotFollower::cmdpub_ [private] |
Definition at line 177 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::goal_z_ [private] |
The distance away from the robot to hold the centroid
Definition at line 72 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::max_x_ [private] |
The maximum x position of the points in the box.
Definition at line 70 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::max_y_ [private] |
The maximum y position of the points in the box.
Definition at line 68 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::max_z_ [private] |
The maximum z position of the points in the box.
Definition at line 71 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::min_x_ [private] |
The minimum x position of the points in the box.
Definition at line 69 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::min_y_ [private] |
The minimum y position of the points in the box.
Definition at line 67 of file follower.cpp.
dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>* turtlebot_follower::TurtlebotFollower::srv_ [private] |
Definition at line 78 of file follower.cpp.
ros::Subscriber turtlebot_follower::TurtlebotFollower::sub_ [private] |
Definition at line 176 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::x_scale_ [private] |
The scaling factor for rotational robot speed
Definition at line 74 of file follower.cpp.
double turtlebot_follower::TurtlebotFollower::z_scale_ [private] |
The scaling factor for translational robot speed
Definition at line 73 of file follower.cpp.