![]() |
Autonomous Racing
1
f1tenth Project Group of Technical University Dortmund, Germany
|
#include <drive_parameters_source.h>
Public Member Functions | |
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 local variables. More... | |
bool | isOutdated () |
Returns true if no update was received for a certain time, determined by the timeout variable. More... | |
bool | isIdle () |
Returns true if the last update contained values close to 0 for both steering and throttle. If no update was received yet, this returns true. More... | |
DriveMode | getDriveMode () |
Definition at line 19 of file drive_parameters_source.h.
DriveParametersSource::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 local variables.
node_handle | A node handle is needed to create a topic subscriber |
topic | The name of the drive_param topic to subscribe to |
update_callback | Callback function that will be called whenever a message was received |
priority | Priority of the source. If multiple sources are not idle, the source with the highest priority is forwarded. |
timeout | Messages will be deferred when they are older than this, in seconds. |
Definition at line 4 of file drive_parameters_source.cpp.
DriveMode DriveParametersSource::getDriveMode | ( | ) |
Definition at line 41 of file drive_parameters_source.cpp.
bool DriveParametersSource::isIdle | ( | ) |
Returns true if the last update contained values close to 0 for both steering and throttle. If no update was received yet, this returns true.
Definition at line 36 of file drive_parameters_source.cpp.
bool DriveParametersSource::isOutdated | ( | ) |
Returns true if no update was received for a certain time, determined by the timeout variable.
Definition at line 27 of file drive_parameters_source.cpp.