Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
vehicle.cpp
Go to the documentation of this file.
1
#include "
adapter_planning/vehicle.hpp
"
2
3
#include "
planning/planning.hpp
"
// Add this line
4
5
VehicleAdapter::VehicleAdapter
(
const
PlanningParameters
& params) :
Planning
(params) {
6
this->
mission_subscription_
=
7
this->create_subscription<custom_interfaces::msg::OperationalStatus>(
8
"/vehicle/operational_status"
, 10,
9
std::bind(&
VehicleAdapter::mission_state_callback
,
this
, std::placeholders::_1));
10
RCLCPP_DEBUG(this->get_logger(),
"Planning : Vehicle adapter created"
);
11
}
12
13
void
VehicleAdapter::mission_state_callback
(
const
custom_interfaces::msg::OperationalStatus& msg) {
14
this->
mission_
=
common_lib::competition_logic::Mission
(msg.as_mission);
15
}
16
17
void
VehicleAdapter::finish
() {
18
RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"
),
"Planning : VehicleAdapter::finish()"
);
19
}
Planning
Responsible for path planning and trajectory generation for the autonomous vehicle.
Definition
planning.hpp:54
Planning::mission_
Mission mission_
Definition
planning.hpp:92
Planning::VehicleAdapter
friend class VehicleAdapter
Definition
planning.hpp:88
VehicleAdapter::mission_state_callback
void mission_state_callback(const custom_interfaces::msg::OperationalStatus &msg)
Definition
vehicle.cpp:13
VehicleAdapter::mission_subscription_
rclcpp::Subscription< custom_interfaces::msg::OperationalStatus >::SharedPtr mission_subscription_
Definition
vehicle.hpp:8
VehicleAdapter::finish
void finish() final
Function that sends the finish signal to the respective node.
Definition
vehicle.cpp:76
common_lib::competition_logic::Mission
Mission
Definition
mission_logic.hpp:11
vehicle.hpp
planning.hpp
PlanningParameters
Definition
planning_config.hpp:11
src
planning
src
adapter_planning
vehicle.cpp
Generated by
1.9.8