34 #ifndef YOCS_DIFF_DRIVE_POSE_CONTROLLER_ROS_HPP_ 35 #define YOCS_DIFF_DRIVE_POSE_CONTROLLER_ROS_HPP_ 41 #include <std_msgs/Empty.h> 42 #include <std_msgs/Float32.h> 43 #include <std_msgs/String.h> 127 void enableCB(
const std_msgs::StringConstPtr msg);
133 void disableCB(
const std_msgs::EmptyConstPtr msg);
ros::Subscriber disable_controller_subscriber_
subscriber for disabling the controller
bool init()
Set-up necessary publishers/subscribers and variables.
A controller for driving a differential drive base to a pose goal or along a path specified by multip...
bool getPoseDiff()
Determines the pose difference in polar coordinates.
DiffDrivePoseControllerROS(ros::NodeHandle &nh, std::string &name)
tf::TransformListener tf_listener_
tf used to get goal pose relative to the base pose
ros::Subscriber enable_controller_subscriber_
subscriber for enabling the controller
void setControlOutput()
Calculates the controller output based on the current pose difference.
std::string base_frame_name_
frame name of the base
tf::StampedTransform tf_goal_pose_rel_
transform for the goal pose relative to the base pose
A controller for driving a differential drive base to a pose goal or along a path specified by multip...
void controlMaxVelCB(const std_msgs::Float32ConstPtr msg)
Callback for updating the controller's maximum linear control velocity.
void spinOnce()
Calculates velocity commands to move the diff-drive base to the (next) pose goal. ...
virtual void onGoalReached()
Publishes goal is reached message.
ros::Publisher pose_reached_publisher_
publishes the status of the goal pose tracking
ros::Publisher command_velocity_publisher_
publisher for sending out base velocity commands
std::string goal_frame_name_
frame name of the goal (pose)
ros::Subscriber control_velocity_subscriber_
subscriber for setting the controller's linear velocity
void enableCB(const std_msgs::StringConstPtr msg)
Callback for enabling the controler.
virtual ~DiffDrivePoseControllerROS()
void disableCB(const std_msgs::EmptyConstPtr msg)
Callback for disabling the controler.