31 #ifndef UBIQUITY_MOTOR_MOTOR_PARMETERS_H 32 #define UBIQUITY_MOTOR_MOTOR_PARMETERS_H 39 T value = default_val;
40 if (!nh.
getParam(parameter_name, value)) {
55 : pid_proportional(5000),
58 pid_denominator(1000),
59 pid_moving_buffer_size(10),
60 deadman_timer(2400000){};
63 : pid_proportional(5000),
66 pid_denominator(1000),
67 pid_moving_buffer_size(10),
68 deadman_timer(2400000) {
71 nh,
"ubiquity_motor/pid_proportional", pid_proportional);
73 nh,
"ubiquity_motor/pid_integral", pid_integral);
75 nh,
"ubiquity_motor/pid_derivative", pid_derivative);
77 nh,
"ubiquity_motor/pid_denominator", pid_denominator);
79 nh,
"ubiquity_motor/window_size", pid_moving_buffer_size);
81 nh,
"ubiquity_motor/deadman_timer", deadman_timer);
92 : serial_port(
"/dev/ttyS0"), baud_rate(9600), serial_loop_rate(100.0){};
95 : serial_port(
"/dev/ttyS0"), baud_rate(9600), serial_loop_rate(100.0) {
98 nh,
"ubiquity_motor/serial_port", serial_port);
100 nh,
"ubiquity_motor/serial_baud", baud_rate);
102 nh,
"ubiquity_motor/serial_loop_rate", serial_loop_rate);
114 nh,
"ubiquity_motor/controller_loop_rate", controller_loop_rate);
119 #endif // UBIQUITY_MOTOR_MOTOR_PARMETERS_H
double controller_loop_rate
CommsParams(ros::NodeHandle nh)
int32_t pid_moving_buffer_size
FirmwareParams(ros::NodeHandle nh)
T getParamOrDefault(ros::NodeHandle nh, std::string parameter_name, T default_val)
bool getParam(const std::string &key, std::string &s) const
NodeParams(ros::NodeHandle nh)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const