Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
velocity_deadband_critic.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_mppi_controller/critics/velocity_deadband_critic.hpp"
16 
17 namespace mppi::critics
18 {
19 
21 {
22  auto getParam = parameters_handler_->getParamGetter(name_);
23 
24  getParam(power_, "cost_power", 1);
25  getParam(weight_, "cost_weight", 35.0);
26 
27  // Recast double to float
28  std::vector<double> deadband_velocities{0.0, 0.0, 0.0};
29  getParam(deadband_velocities, "deadband_velocities", std::vector<double>{0.0, 0.0, 0.0});
30  std::transform(
31  deadband_velocities.begin(), deadband_velocities.end(), deadband_velocities_.begin(),
32  [](double d) {return static_cast<float>(d);});
33 
34  RCLCPP_INFO_STREAM(
35  logger_, "VelocityDeadbandCritic instantiated with "
36  << power_ << " power, " << weight_ << " weight, deadband_velocity ["
37  << deadband_velocities_.at(0) << "," << deadband_velocities_.at(1) << ","
38  << deadband_velocities_.at(2) << "]");
39 }
40 
42 {
43  if (!enabled_) {
44  return;
45  }
46 
47  if (data.motion_model->isHolonomic()) {
48  if (power_ > 1u) {
49  data.costs += ((((fabs(deadband_velocities_[0]) - data.state.vx.abs()).max(0.0f) +
50  (fabs(deadband_velocities_[1]) - data.state.vy.abs()).max(0.0f) +
51  (fabs(deadband_velocities_[2]) - data.state.wz.abs()).max(0.0f)) *
52  data.model_dt).rowwise().sum() * weight_).pow(power_).eval();
53  } else {
54  data.costs += ((((fabs(deadband_velocities_[0]) - data.state.vx.abs()).max(0.0f) +
55  (fabs(deadband_velocities_[1]) - data.state.vy.abs()).max(0.0f) +
56  (fabs(deadband_velocities_[2]) - data.state.wz.abs()).max(0.0f)) *
57  data.model_dt).rowwise().sum() * weight_).eval();
58  }
59  return;
60  }
61 
62  if (power_ > 1u) {
63  data.costs += ((((fabs(deadband_velocities_[0]) - data.state.vx.abs()).max(0.0f) +
64  (fabs(deadband_velocities_[2]) - data.state.wz.abs()).max(0.0f)) *
65  data.model_dt).rowwise().sum() * weight_).pow(power_).eval();
66  } else {
67  data.costs += ((((fabs(deadband_velocities_[0]) - data.state.vx.abs()).max(0.0f) +
68  (fabs(deadband_velocities_[2]) - data.state.wz.abs()).max(0.0f)) *
69  data.model_dt).rowwise().sum() * weight_).eval();
70  }
71  return;
72 }
73 
74 } // namespace mppi::critics
75 
76 #include <pluginlib/class_list_macros.hpp>
77 
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
Abstract critic objective function to score trajectories.
Critic objective function for enforcing feasible constraints.
void initialize() override
Initialize critic.
void score(CriticData &data) override
Evaluate cost related to goal following.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:40