|
1 | 1 |
|
2 |
| -// Copyright 2022 TIER IV, Inc. |
| 2 | +// Copyright 2022-2024 TIER IV, Inc. |
3 | 3 | //
|
4 | 4 | // Licensed under the Apache License, Version 2.0 (the "License");
|
5 | 5 | // you may not use this file except in compliance with the License.
|
|
13 | 13 | // See the License for the specific language governing permissions and
|
14 | 14 | // limitations under the License.
|
15 | 15 |
|
16 |
| -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ |
17 |
| -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ |
| 16 | +#ifndef MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ |
| 17 | +#define MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ |
18 | 18 |
|
19 | 19 | #include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
|
20 | 20 | #include <autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
|
|
25 | 25 | #include <string>
|
26 | 26 | #include <vector>
|
27 | 27 |
|
28 |
| -namespace behavior_velocity_planner |
| 28 | +namespace motion_utils |
29 | 29 | {
|
30 |
| - |
31 | 30 | using autoware_adapi_v1_msgs::msg::PlanningBehavior;
|
32 | 31 | using autoware_adapi_v1_msgs::msg::VelocityFactor;
|
33 |
| -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; |
34 |
| -using geometry_msgs::msg::Pose; |
35 | 32 | using VelocityFactorBehavior = VelocityFactor::_behavior_type;
|
36 | 33 | using VelocityFactorStatus = VelocityFactor::_status_type;
|
| 34 | +using geometry_msgs::msg::Pose; |
37 | 35 |
|
38 | 36 | class VelocityFactorInterface
|
39 | 37 | {
|
40 | 38 | public:
|
41 |
| - VelocityFactorInterface() { behavior_ = VelocityFactor::UNKNOWN; } |
42 |
| - |
43 |
| - VelocityFactor get() const { return velocity_factor_; } |
44 |
| - void init(const VelocityFactorBehavior behavior) { behavior_ = behavior; } |
| 39 | + [[nodiscard]] VelocityFactor get() const { return velocity_factor_; } |
| 40 | + void init(const VelocityFactorBehavior & behavior) { behavior_ = behavior; } |
45 | 41 | void reset() { velocity_factor_.behavior = PlanningBehavior::UNKNOWN; }
|
46 | 42 |
|
47 | 43 | void set(
|
48 | 44 | const std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId> & points,
|
49 | 45 | const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status,
|
50 |
| - const std::string detail = ""); |
| 46 | + const std::string & detail = ""); |
51 | 47 |
|
52 | 48 | private:
|
53 |
| - VelocityFactorBehavior behavior_; |
54 |
| - VelocityFactor velocity_factor_; |
| 49 | + VelocityFactorBehavior behavior_{VelocityFactor::UNKNOWN}; |
| 50 | + VelocityFactor velocity_factor_{}; |
55 | 51 | };
|
56 | 52 |
|
57 |
| -} // namespace behavior_velocity_planner |
| 53 | +} // namespace motion_utils |
58 | 54 |
|
59 |
| -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ |
| 55 | +#endif // MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ |
0 commit comments