ros2_rover
Loading...
Searching...
No Matches
motors_command_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 MOTORS_COMMANDS_NODE_HPP
24#define MOTORS_COMMANDS_NODE_HPP
25
26#include "rclcpp/rclcpp.hpp"
27#include "std_msgs/msg/float64_multi_array.hpp"
28
29#include "rover_msgs/msg/motors_command.hpp"
30
31class MotorsCommandParserNode : public rclcpp::Node {
32public:
34 void callback(const rover_msgs::msg::MotorsCommand::SharedPtr msg);
35 int clamp(int range_min, int range_max, int value);
36 float normalize(int range_min, int range_max, int value);
37
38private:
39 rclcpp::Subscription<rover_msgs::msg::MotorsCommand>::SharedPtr subscription;
40 rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr
42 rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr
44};
45
46#endif
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr position_publisher
Definition motors_command_parser_node.hpp:43
void callback(const rover_msgs::msg::MotorsCommand::SharedPtr msg)
Definition motors_command_parser_node.cpp:52
int clamp(int range_min, int range_max, int value)
Definition motors_command_parser_node.cpp:93
rclcpp::Subscription< rover_msgs::msg::MotorsCommand >::SharedPtr subscription
Definition motors_command_parser_node.hpp:39
MotorsCommandParserNode()
Definition motors_command_parser_node.cpp:35
float normalize(int range_min, int range_max, int value)
Definition motors_command_parser_node.cpp:97
rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr velocity_publisher
Definition motors_command_parser_node.hpp:41