12 #include <nav_msgs/Odometry.h> 13 #include <geometry_msgs/Twist.h> 17 #ifndef _YOCS_BASIC_MOVE_CONTROLLER_HPP_ 18 #define _YOCS_BASIC_MOVE_CONTROLLER_HPP_ 30 void moveAt(
double v,
double w,
double t);
42 void turn2(
double angle);
void backward(double distance)
BasicMoveController(ros::NodeHandle &n)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void moveAt(double v, double w, double t)
void turnCounterClockwise()
std::string cmd_vel_topic_
void processOdometry(const nav_msgs::Odometry::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & w() const
std::string odometry_topic_
virtual ~BasicMoveController()
void forward(double distance)
ros::Subscriber sub_odom_
void spinCounterClockwise()
nav_msgs::Odometry odometry_
ros::Publisher pub_cmd_vel_