Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
drive_parameters_source.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "drive_mode.h"
4 #include <ros/ros.h>
5 
6 #include <drive_msgs/drive_param.h>
7 #include <functional>
8 #include <std_msgs/Float64.h>
9 
12  std::function<void(DriveParametersSource*, const drive_msgs::drive_param::ConstPtr&)>;
13 
14 constexpr float IDLE_RANGE = 0.01f;
15 
16 /*
17  * A class that listens on a topic that publishes drive parameters and stores information about that source
18  */
20 {
21  public:
33  DriveParametersSource(ros::NodeHandle* node_handle, const char* topic,
34  DriveParameterCallbackFunction update_callback, DriveMode drive_mode, ros::Duration timeout);
35 
39  bool isOutdated();
40 
45  bool isIdle();
46 
48 
49  private:
50  ros::Subscriber m_drive_parameters_subscriber;
51 
52  DriveMode m_drive_mode;
53  bool m_idle;
54  ros::Duration m_timeout;
55  ros::Time m_last_update;
56 
57  DriveParameterCallbackFunction m_updateCallback;
58 
59  void driveParametersCallback(const drive_msgs::drive_param::ConstPtr& parameters);
60 };
constexpr float IDLE_RANGE
bool isOutdated()
Returns true if no update was received for a certain time, determined by the timeout variable...
DriveMode
Definition: drive_mode.h:3
DriveParametersSource(ros::NodeHandle *node_handle, const char *topic, DriveParameterCallbackFunction update_callback, DriveMode drive_mode, ros::Duration timeout)
Construct a new DriveParametersSource object, subscribes to the topic and stores the parameters into ...
bool isIdle()
Returns true if the last update contained values close to 0 for both steering and throttle...
std::function< void(DriveParametersSource *, const drive_msgs::drive_param::ConstPtr &)> DriveParameterCallbackFunction