ros2_rover
Loading...
Searching...
No Matches
vel_parser_node.hpp
Go to the documentation of this file.
1// MIT License
2
3// Copyright (c) 2023 Miguel Ángel González Santamarta
4
5// Permission is hereby granted, free of charge, to any person obtaining a copy
6// of this software and associated documentation files (the "Software"), to deal
7// in the Software without restriction, including without limitation the rights
8// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9// copies of the Software, and to permit persons to whom the Software is
10// furnished to do so, subject to the following conditions:
11
12// The above copyright notice and this permission notice shall be included in
13// all copies or substantial portions of the Software.
14
15// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21// SOFTWARE.
22
23#ifndef CONTROLLER_NODE_HPP
24#define CONTROLLER_NODE_HPP
25
26#include "geometry_msgs/msg/twist.hpp"
27#include "rclcpp/rclcpp.hpp"
28
29#include "rover_msgs/msg/motors_command.hpp"
30
31#define MAX_RADIUS 255
32#define MIN_RADIUS 55
33
34namespace motor_controller {
35
36class VelParserNode : public rclcpp::Node {
37public:
39 void callback(const geometry_msgs::msg::Twist::SharedPtr msg);
40
41 float normalize(float value, float old_min, float old_max, float new_min,
42 float new_max);
43 float deg_to_tick(float deg, float e_min, float e_max);
44 float radians_to_deg(float radians);
45
46 std::vector<float> calculate_velocity(float velocity, float radius);
47 std::vector<float> calculate_target_deg(float radius);
48 std::vector<float> calculate_target_tick(std::vector<float> target_angles);
49
50private:
51 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription;
52 rclcpp::Publisher<rover_msgs::msg::MotorsCommand>::SharedPtr publisher;
54 float d1;
55 float d2;
56 float d3;
57 float d4;
60 float enc_mid;
64};
65
66} // namespace motor_controller
67#endif
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