
| Public Member Functions | |
| RochFollower () | |
| The constructor for the follower. Constructor for the follower.  More... | |
| ~RochFollower () | |
|  Public Member Functions inherited from nodelet::Nodelet | |
| void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) | 
| Nodelet () | |
| virtual | ~Nodelet () | 
| Private Member Functions | |
| bool | changeModeSrvCb (roch_msgs::SetFollowState::Request &request, roch_msgs::SetFollowState::Response &response) | 
| void | imagecb (const sensor_msgs::ImageConstPtr &depth_msg) | 
| Callback for point clouds. Callback for depth images. It finds the centroid of the points in a box in the center of the image. Publishes cmd_vel messages with the goal from the image.  More... | |
| virtual void | onInit () | 
| OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics.  More... | |
| void | publishBbox () | 
| void | publishMarker (double x, double y, double z) | 
| void | reconfigure (roch_follower::FollowerConfig &config, uint32_t level) | 
| Private Attributes | |
| ros::Publisher | bboxpub_ | 
| ros::Publisher | cmdpub_ | 
| dynamic_reconfigure::Server< roch_follower::FollowerConfig > * | config_srv_ | 
| bool | enabled_ | 
| double | goal_z_ | 
| ros::Publisher | markerpub_ | 
| double | max_x_ | 
| double | max_y_ | 
| double | max_z_ | 
| double | min_x_ | 
| double | min_y_ | 
| ros::Subscriber | sub_ | 
| ros::ServiceServer | switch_srv_ | 
| double | x_scale_ | 
| double | z_scale_ | 
| Additional Inherited Members | |
|  Protected Member Functions inherited from nodelet::Nodelet | |
| ros::CallbackQueueInterface & | getMTCallbackQueue () const | 
| ros::NodeHandle & | getMTNodeHandle () const | 
| ros::NodeHandle & | getMTPrivateNodeHandle () const | 
| const V_string & | getMyArgv () const | 
| const std::string & | getName () const | 
| ros::NodeHandle & | getNodeHandle () const | 
| ros::NodeHandle & | getPrivateNodeHandle () const | 
| const M_string & | getRemappingArgs () const | 
| ros::CallbackQueueInterface & | getSTCallbackQueue () const | 
| std::string | getSuffixedName (const std::string &suffix) const | 
The roch follower nodelet. Subscribes to point clouds from the 3dsensor, processes them, and publishes command vel messages.
Definition at line 53 of file follower.cpp.
| 
 | inline | 
The constructor for the follower. Constructor for the follower.
Definition at line 60 of file follower.cpp.
| 
 | inline | 
Definition at line 68 of file follower.cpp.
| 
 | inlineprivate | 
Definition at line 230 of file follower.cpp.
| 
 | inlineprivate | 
Callback for point clouds. Callback for depth images. It finds the centroid of the points in a box in the center of the image. Publishes cmd_vel messages with the goal from the image.
| cloud | The point cloud message. | 
Definition at line 142 of file follower.cpp.
| 
 | inlineprivatevirtual | 
OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics.
Implements nodelet::Nodelet.
Definition at line 95 of file follower.cpp.
| 
 | inlineprivate | 
Definition at line 276 of file follower.cpp.
| 
 | inlineprivate | 
Definition at line 249 of file follower.cpp.
| 
 | inlineprivate | 
Definition at line 123 of file follower.cpp.
| 
 | private | 
Definition at line 314 of file follower.cpp.
| 
 | private | 
Definition at line 312 of file follower.cpp.
| 
 | private | 
Definition at line 88 of file follower.cpp.
| 
 | private | 
Enable/disable following; just prevents motor commands
Definition at line 82 of file follower.cpp.
| 
 | private | 
The distance away from the robot to hold the centroid
Definition at line 79 of file follower.cpp.
| 
 | private | 
Definition at line 313 of file follower.cpp.
| 
 | private | 
The maximum x position of the points in the box.
Definition at line 77 of file follower.cpp.
| 
 | private | 
The maximum y position of the points in the box.
Definition at line 75 of file follower.cpp.
| 
 | private | 
The maximum z position of the points in the box.
Definition at line 78 of file follower.cpp.
| 
 | private | 
The minimum x position of the points in the box.
Definition at line 76 of file follower.cpp.
| 
 | private | 
The minimum y position of the points in the box.
Definition at line 74 of file follower.cpp.
| 
 | private | 
Definition at line 311 of file follower.cpp.
| 
 | private | 
Definition at line 85 of file follower.cpp.
| 
 | private | 
The scaling factor for rotational robot speed
Definition at line 81 of file follower.cpp.
| 
 | private | 
The scaling factor for translational robot speed
Definition at line 80 of file follower.cpp.