basic_move_controller.hpp
Go to the documentation of this file.
1 /*
2  * basic_move_controller.hpp
3  * LICENSE : BSD - https://raw.github.com/yujinrobot/yujin_ocs/license/LICENSE
4  */
5 
6 #include <ros/ros.h>
7 #include <tf/tf.h>
8 
11 
12 #include <nav_msgs/Odometry.h>
13 #include <geometry_msgs/Twist.h>
14 
16 
17 #ifndef _YOCS_BASIC_MOVE_CONTROLLER_HPP_
18 #define _YOCS_BASIC_MOVE_CONTROLLER_HPP_
19 
20 namespace yocs_navigator {
22  public:
24  BasicMoveController(ros::NodeHandle& n, const std::string& twist_topic, const std::string& odometry_topic);
25  virtual ~BasicMoveController();
26 
27  void init();
28 
29  // linear, angualr, time
30  void moveAt(double v, double w, double t);
31 
32  void slowForward();
33  void slowBackward();
34  void turnClockwise();
35  void turnCounterClockwise();
36  void stop();
37 
38  void forward(double distance);
39  void backward(double distance);
40  void turn(double angle);
41 
42  void turn2(double angle);
43  void spinClockwise();
44  void spinCounterClockwise();
45  protected:
46  void processOdometry(const nav_msgs::Odometry::ConstPtr& msg);
47 
48  private:
52 
53  nav_msgs::Odometry odometry_;
54  std::string cmd_vel_topic_;
55  std::string odometry_topic_;
56 };
57 }
58 #endif
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 processOdometry(const nav_msgs::Odometry::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & w() const


yocs_navigator
Author(s): Jihoon Lee, Jorge Simon Santos
autogenerated on Mon Jun 10 2019 15:53:58