ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
p_odometrymodel.h
Go to the documentation of this file.
1 /********************************************************************************
2  * Copyright (C) 2017-2021 German Aerospace Center (DLR).
3  * Eclipse ADORe, Automated Driving Open Research https://eclipse.org/adore
4  *
5  * This program and the accompanying materials are made available under the
6  * terms of the Eclipse Public License 2.0 which is available at
7  * http://www.eclipse.org/legal/epl-2.0.
8  *
9  * SPDX-License-Identifier: EPL-2.0
10  *
11  * Contributors:
12  * Daniel Heß - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
17 #include <ros/ros.h>
20 
21 namespace adore
22 {
23  namespace if_ROS
24  {
25  namespace params
26  {
28  {
29  public:
30  POdometryModel(ros::NodeHandle n,std::string prefix)
31  :ROSParam(n,prefix + "OdometryModel/")
32  {
33  }
34  virtual double get_k_e_vx()const override
35  {
36  double value = 0.0;
37  static const std::string name = prefix_ + "k_e_vx";
38  get(name,value);
39  return value;
40  }
41  virtual double get_k_e_vy()const override
42  {
43  double value = 0.0;
44  static const std::string name = prefix_ + "k_e_vy";
45  get(name,value);
46  return value;
47  }
48  virtual double get_k_e_omega()const override
49  {
50  double value = 0.0;
51  static const std::string name = prefix_ + "k_e_omega";
52  get(name,value);
53  return value;
54  }
55  virtual double get_k_e_ax()const override
56  {
57  double value = 0.0;
58  static const std::string name = prefix_ + "k_e_ax";
59  get(name,value);
60  return value;
61  }
62 
63  };
64  }
65  }
66 }
Definition: ros_com_patterns.h:179
std::string prefix_
Definition: ros_com_patterns.h:181
void get(const std::string &name, T &result) const
Definition: ros_com_patterns.h:186
Definition: p_odometrymodel.h:28
virtual double get_k_e_omega() const override
Definition: p_odometrymodel.h:48
POdometryModel(ros::NodeHandle n, std::string prefix)
Definition: p_odometrymodel.h:30
virtual double get_k_e_vx() const override
Definition: p_odometrymodel.h:34
virtual double get_k_e_ax() const override
Definition: p_odometrymodel.h:55
virtual double get_k_e_vy() const override
Definition: p_odometrymodel.h:41
abstract class containing parameters which configure odometry state estimation model
Definition: ap_odometrymodel.h:26
Definition: areaofeffectconverter.h:20