23#ifndef MOTORS_COMMANDS_NODE_HPP
24#define MOTORS_COMMANDS_NODE_HPP
26#include "rclcpp/rclcpp.hpp"
27#include "std_msgs/msg/float64_multi_array.hpp"
29#include "rover_msgs/msg/motors_command.hpp"
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);
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
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