23#ifndef CONTROLLER_NODE_HPP
24#define CONTROLLER_NODE_HPP
26#include "geometry_msgs/msg/twist.hpp"
27#include "rclcpp/rclcpp.hpp"
29#include "rover_msgs/msg/motors_command.hpp"
39 void callback(
const geometry_msgs::msg::Twist::SharedPtr msg);
41 float normalize(
float value,
float old_min,
float old_max,
float new_min,
43 float deg_to_tick(
float deg,
float e_min,
float e_max);
51 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
subscription;
52 rclcpp::Publisher<rover_msgs::msg::MotorsCommand>::SharedPtr
publisher;
float radians_to_deg(float radians)
Definition vel_parser_node.cpp:134
int enc_min
Definition vel_parser_node.hpp:58
rclcpp::Publisher< rover_msgs::msg::MotorsCommand >::SharedPtr publisher
Definition vel_parser_node.hpp:52
std::vector< float > calculate_target_tick(std::vector< float > target_angles)
Definition vel_parser_node.cpp:256
float d1
Definition vel_parser_node.hpp:54
int speed_factor
Definition vel_parser_node.hpp:53
int enc_max
Definition vel_parser_node.hpp:59
std::vector< float > calculate_velocity(float velocity, float radius)
Definition vel_parser_node.cpp:139
float angular_factor
Definition vel_parser_node.hpp:63
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr subscription
Definition vel_parser_node.hpp:51
std::vector< float > calculate_target_deg(float radius)
Definition vel_parser_node.cpp:210
float d2
Definition vel_parser_node.hpp:55
float enc_mid
Definition vel_parser_node.hpp:60
float angular_limit
Definition vel_parser_node.hpp:62
void callback(const geometry_msgs::msg::Twist::SharedPtr msg)
Definition vel_parser_node.cpp:78
float normalize(float value, float old_min, float old_max, float new_min, float new_max)
Definition vel_parser_node.cpp:117
VelParserNode()
Definition vel_parser_node.cpp:37
float deg_to_tick(float deg, float e_min, float e_max)
Definition vel_parser_node.cpp:123
float d4
Definition vel_parser_node.hpp:57
float linear_limit
Definition vel_parser_node.hpp:61
float d3
Definition vel_parser_node.hpp:56
Definition controller_node.hpp:33