Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
vesc_sim.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 #include <string>
5 #include <tf/transform_broadcaster.h>
6 
8 {
9  public:
10  VESCSimulator();
11  inline void setServoAngle(const double& data)
12  {
13  this->m_servo_data = data;
14  }
15  inline void setSpeed(const double& data)
16  {
17  this->m_state_speed = data;
18  }
19  void start();
20  void stop();
21 
22  private:
23  ros::NodeHandle m_node_handle;
24  ros::Publisher m_odometry_publisher;
25  tf::TransformBroadcaster m_tf_publisher;
26  ros::Timer m_timer;
27  ros::Time m_last_stamp;
28 
29  bool m_started;
30  double m_yaw;
31  double m_servo_data;
32  double m_state_speed;
33  double m_x_position;
34  double m_y_position;
35  double m_x_dot;
36  double m_y_dot;
37  double m_current_speed;
38  double m_current_steering_angle;
39  double m_current_angular_velocity;
40  double m_frequency;
41  std::string m_odom_frame;
42  std::string m_base_frame;
43 
44  void timerCallback(const ros::TimerEvent& event);
45 };
void start()
Definition: vesc_sim.cpp:28
void setSpeed(const double &data)
Definition: vesc_sim.h:15
void setServoAngle(const double &data)
Definition: vesc_sim.h:11
void stop()
Definition: vesc_sim.cpp:37