12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef VEHICLE_RAW_VEHICLE_CMD_CONVERTER_INCLUDE_RAW_VEHICLE_CMD_CONVERTER_NODE_HPP_
16
- #define VEHICLE_RAW_VEHICLE_CMD_CONVERTER_INCLUDE_RAW_VEHICLE_CMD_CONVERTER_NODE_HPP_
15
+ #ifndef RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
16
+ #define RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
17
+
18
+ #include < memory>
19
+ #include < string>
17
20
18
21
#include " raw_vehicle_cmd_converter/accel_map.hpp"
19
22
#include " raw_vehicle_cmd_converter/brake_map.hpp"
25
28
#include " autoware_vehicle_msgs/msg/shift.hpp"
26
29
#include " autoware_vehicle_msgs/msg/vehicle_command.hpp"
27
30
28
- #include < memory>
29
- #include < string>
30
31
31
32
class AccelMapConverter : public rclcpp ::Node
32
33
{
@@ -35,17 +36,23 @@ class AccelMapConverter : public rclcpp::Node
35
36
~AccelMapConverter () = default ;
36
37
37
38
private:
38
- rclcpp::Publisher<autoware_vehicle_msgs::msg::RawVehicleCommand>::SharedPtr pub_cmd_; // !< @brief topic publisher for low-level vehicle command
39
- rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr sub_velocity_; // !< @brief subscriber for current velocity
40
- rclcpp::Subscription<autoware_vehicle_msgs::msg::VehicleCommand>::SharedPtr sub_cmd_; // !< @brief subscriber for vehicle command
39
+ rclcpp::Publisher<autoware_vehicle_msgs::msg::RawVehicleCommand>::SharedPtr
40
+ pub_cmd_; // !< @brief topic publisher for low-level vehicle command
41
+ rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr
42
+ sub_velocity_; // !< @brief subscriber for current velocity
43
+ rclcpp::Subscription<autoware_vehicle_msgs::msg::VehicleCommand>::SharedPtr
44
+ sub_cmd_; // !< @brief subscriber for vehicle command
41
45
42
46
std::shared_ptr<double > current_velocity_ptr_; // [m/s]
43
47
44
48
AccelMap accel_map_;
45
49
BrakeMap brake_map_;
46
- bool acc_map_initialized_; // !< @brief flag to manage validity of imported accel map files
47
- double max_throttle_; // !< @brief maximum throttle that can be passed to low level controller. In general [0.0, 1.0]
48
- double max_brake_; // !< @brief maximum brake value that can be passed to low level controller. In general [0.0, 1.0]
50
+ // !< @brief flag to manage validity of imported accel map files
51
+ bool acc_map_initialized_;
52
+ // !< @brief maximum throttle that can be passed to low level controller. In general [0.0, 1.0]
53
+ double max_throttle_;
54
+ // !< @brief maximum brake value that can be passed to low level controller. In general [0.0, 1.0]
55
+ double max_brake_;
49
56
50
57
void callbackVehicleCmd (
51
58
const autoware_vehicle_msgs::msg::VehicleCommand::ConstSharedPtr vehicle_cmd_ptr);
@@ -55,4 +62,4 @@ class AccelMapConverter : public rclcpp::Node
55
62
double * desired_brake);
56
63
};
57
64
58
- #endif // VEHICLE_RAW_VEHICLE_CMD_CONVERTER_INCLUDE_RAW_VEHICLE_CMD_CONVERTER_NODE_HPP_
65
+ #endif // RAW_VEHICLE_CMD_CONVERTER__NODE_HPP_
0 commit comments