motor_parmeters.h
Go to the documentation of this file.
1 
31 #ifndef UBIQUITY_MOTOR_MOTOR_PARMETERS_H
32 #define UBIQUITY_MOTOR_MOTOR_PARMETERS_H
33 
34 #include <ros/ros.h>
35 
36 template <typename T>
37 T getParamOrDefault(ros::NodeHandle nh, std::string parameter_name,
38  T default_val) {
39  T value = default_val;
40  if (!nh.getParam(parameter_name, value)) {
41  nh.setParam(parameter_name, value);
42  }
43  return value;
44 }
45 
48  int32_t pid_integral;
49  int32_t pid_derivative;
50  int32_t pid_denominator;
52  int32_t deadman_timer;
53 
55  : pid_proportional(5000),
56  pid_integral(10),
57  pid_derivative(1),
58  pid_denominator(1000),
59  pid_moving_buffer_size(10),
60  deadman_timer(2400000){};
61 
63  : pid_proportional(5000),
64  pid_integral(10),
65  pid_derivative(1),
66  pid_denominator(1000),
67  pid_moving_buffer_size(10),
68  deadman_timer(2400000) {
69  // clang-format off
70  pid_proportional = getParamOrDefault(
71  nh, "ubiquity_motor/pid_proportional", pid_proportional);
72  pid_integral = getParamOrDefault(
73  nh, "ubiquity_motor/pid_integral", pid_integral);
74  pid_derivative = getParamOrDefault(
75  nh, "ubiquity_motor/pid_derivative", pid_derivative);
76  pid_denominator = getParamOrDefault(
77  nh, "ubiquity_motor/pid_denominator", pid_denominator);
78  pid_moving_buffer_size = getParamOrDefault(
79  nh, "ubiquity_motor/window_size", pid_moving_buffer_size);
80  deadman_timer = getParamOrDefault(
81  nh, "ubiquity_motor/deadman_timer", deadman_timer);
82  // clang-format on
83  };
84 };
85 
86 struct CommsParams {
87  std::string serial_port;
88  int32_t baud_rate;
90 
92  : serial_port("/dev/ttyS0"), baud_rate(9600), serial_loop_rate(100.0){};
93 
95  : serial_port("/dev/ttyS0"), baud_rate(9600), serial_loop_rate(100.0) {
96  // clang-format off
97  serial_port = getParamOrDefault(
98  nh, "ubiquity_motor/serial_port", serial_port);
99  baud_rate = getParamOrDefault(
100  nh, "ubiquity_motor/serial_baud", baud_rate);
101  serial_loop_rate = getParamOrDefault(
102  nh, "ubiquity_motor/serial_loop_rate", serial_loop_rate);
103  // clang-format on
104  };
105 };
106 
107 struct NodeParams {
109 
110  NodeParams() : controller_loop_rate(10.0){};
111  NodeParams(ros::NodeHandle nh) : controller_loop_rate(10.0) {
112  // clang-format off
113  controller_loop_rate = getParamOrDefault(
114  nh, "ubiquity_motor/controller_loop_rate", controller_loop_rate);
115  // clang-format on
116  };
117 };
118 
119 #endif // UBIQUITY_MOTOR_MOTOR_PARMETERS_H
int32_t pid_proportional
int32_t deadman_timer
double controller_loop_rate
CommsParams(ros::NodeHandle nh)
int32_t pid_denominator
int32_t baud_rate
int32_t pid_moving_buffer_size
FirmwareParams(ros::NodeHandle nh)
int32_t pid_integral
int32_t pid_derivative
T getParamOrDefault(ros::NodeHandle nh, std::string parameter_name, T default_val)
double serial_loop_rate
bool getParam(const std::string &key, std::string &s) const
std::string serial_port
NodeParams(ros::NodeHandle nh)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


ubiquity_motor
Author(s):
autogenerated on Mon Jun 10 2019 15:37:24