Public Member Functions | Private Member Functions | Private Attributes | List of all members
turtlebot_follower::TurtlebotFollower Class Reference
Inheritance diagram for turtlebot_follower::TurtlebotFollower:
Inheritance graph
[legend]

Public Member Functions

 TurtlebotFollower ()
 The constructor for the follower. Constructor for the follower. More...
 
 ~TurtlebotFollower ()
 
- 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 (turtlebot_msgs::SetFollowState::Request &request, turtlebot_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 (turtlebot_follower::FollowerConfig &config, uint32_t level)
 

Private Attributes

ros::Publisher bboxpub_
 
ros::Publisher cmdpub_
 
dynamic_reconfigure::Server< turtlebot_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::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

The turtlebot follower nodelet. Subscribes to point clouds from the 3dsensor, processes them, and publishes command vel messages.

Definition at line 53 of file follower.cpp.

Constructor & Destructor Documentation

turtlebot_follower::TurtlebotFollower::TurtlebotFollower ( )
inline

The constructor for the follower. Constructor for the follower.

Definition at line 60 of file follower.cpp.

turtlebot_follower::TurtlebotFollower::~TurtlebotFollower ( )
inline

Definition at line 68 of file follower.cpp.

Member Function Documentation

bool turtlebot_follower::TurtlebotFollower::changeModeSrvCb ( turtlebot_msgs::SetFollowState::Request &  request,
turtlebot_msgs::SetFollowState::Response &  response 
)
inlineprivate

Definition at line 230 of file follower.cpp.

void turtlebot_follower::TurtlebotFollower::imagecb ( const sensor_msgs::ImageConstPtr &  depth_msg)
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.

Parameters
cloudThe point cloud message.

Definition at line 142 of file follower.cpp.

virtual void turtlebot_follower::TurtlebotFollower::onInit ( )
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.

void turtlebot_follower::TurtlebotFollower::publishBbox ( )
inlineprivate

Definition at line 276 of file follower.cpp.

void turtlebot_follower::TurtlebotFollower::publishMarker ( double  x,
double  y,
double  z 
)
inlineprivate

Definition at line 249 of file follower.cpp.

void turtlebot_follower::TurtlebotFollower::reconfigure ( turtlebot_follower::FollowerConfig &  config,
uint32_t  level 
)
inlineprivate

Definition at line 123 of file follower.cpp.

Member Data Documentation

ros::Publisher turtlebot_follower::TurtlebotFollower::bboxpub_
private

Definition at line 314 of file follower.cpp.

ros::Publisher turtlebot_follower::TurtlebotFollower::cmdpub_
private

Definition at line 312 of file follower.cpp.

dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>* turtlebot_follower::TurtlebotFollower::config_srv_
private

Definition at line 88 of file follower.cpp.

bool turtlebot_follower::TurtlebotFollower::enabled_
private

Enable/disable following; just prevents motor commands

Definition at line 82 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::goal_z_
private

The distance away from the robot to hold the centroid

Definition at line 79 of file follower.cpp.

ros::Publisher turtlebot_follower::TurtlebotFollower::markerpub_
private

Definition at line 313 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::max_x_
private

The maximum x position of the points in the box.

Definition at line 77 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::max_y_
private

The maximum y position of the points in the box.

Definition at line 75 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::max_z_
private

The maximum z position of the points in the box.

Definition at line 78 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::min_x_
private

The minimum x position of the points in the box.

Definition at line 76 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::min_y_
private

The minimum y position of the points in the box.

Definition at line 74 of file follower.cpp.

ros::Subscriber turtlebot_follower::TurtlebotFollower::sub_
private

Definition at line 311 of file follower.cpp.

ros::ServiceServer turtlebot_follower::TurtlebotFollower::switch_srv_
private

Definition at line 85 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::x_scale_
private

The scaling factor for rotational robot speed

Definition at line 81 of file follower.cpp.

double turtlebot_follower::TurtlebotFollower::z_scale_
private

The scaling factor for translational robot speed

Definition at line 80 of file follower.cpp.


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


turtlebot_follower
Author(s): Tony Pratkanis
autogenerated on Mon Jun 10 2019 15:44:12