SMACC
Loading...
Searching...
No Matches
cb_navigate_forward.h
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6#pragma once
7
9#include <tf/transform_listener.h>
11
12namespace cl_move_base_z
13{
15 {
16 public:
17 boost::optional<float> forwardDistance;
18
19 // just a stub to show how to use parameterless constructor
20 boost::optional<float> forwardSpeed;
21
22 // this may be useful in the case you want to do a stright line with some orientation
23 // relative to some global reference (trying to solve the initial orientation error
24 // of the current orientation). If it is not set, the orientation of the straight line is
25 // the orientation of the initial state.
26 boost::optional<geometry_msgs::Quaternion> forceInitialOrientation;
27
28 tf::TransformListener listener;
29
31
33
35
36 virtual void onEntry() override;
37
38 virtual void onExit() override;
39 };
40} // namespace cl_move_base_z
boost::optional< float > forwardDistance
odom_tracker::OdomTracker * odomTracker_
boost::optional< geometry_msgs::Quaternion > forceInitialOrientation
boost::optional< float > forwardSpeed
This class track the required distance of the cord based on the external localization system.
Definition: odom_tracker.h:47