38 #ifndef ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H 39 #define ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H 42 #include <boost/shared_ptr.hpp> 43 #include <boost/thread/mutex.hpp> 51 #include <geometry_msgs/Twist.h> 52 #include <nav_msgs/Odometry.h> 53 #include <sensor_msgs/LaserScan.h> 92 virtual bool stop(
bool force);
100 virtual bool reset();
112 return "robot_controllers/DiffDriveBaseController";
122 void command(
const geometry_msgs::TwistConstPtr& msg);
129 void scanCallback(
const sensor_msgs::LaserScanConstPtr& scan);
191 #endif // ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H
double rotating_threshold_
Threshold for wheel velocity to be "moving".
boost::mutex command_mutex_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
virtual std::string getType()
Get the type of this controller.
void publishCallback(const ros::TimerEvent &event)
void setCommand(float left, float right)
void command(const geometry_msgs::TwistConstPtr &msg)
Command callback from either a ROS topic, or a higher controller.
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
double max_acceleration_x_
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)
boost::shared_ptr< DiffDriveBaseController > DiffDriveBaseControllerPtr
double right_last_timestamp_
float right_last_position_
double safety_scaling_distance_
double moving_threshold_
Threshold for dr to be considered "moving".
double radians_per_meter_
float left_last_position_
double max_velocity_x_
Threshold for dx to be considered "moving".
double wheel_rotating_threshold_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
double left_last_timestamp_
ros::Subscriber scan_sub_
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
double max_acceleration_r_
boost::shared_ptr< tf::TransformBroadcaster > broadcaster_
ControllerManager * manager_
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
ros::Time last_laser_scan_
ROS-aware controller to manage a differential drive mobile base. This subcribes to cmd_vel topic...
DiffDriveBaseController()
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
virtual ~DiffDriveBaseController()