Common
common packages for kyubic
 
Loading...
Searching...
No Matches
update_mode.hpp
Go to the documentation of this file.
1
10#ifndef _UPDATE_MODE_HPP
11#define _UPDATE_MODE_HPP
12
13#include <behaviortree_cpp/action_node.h>
14
15#include <cstdint>
17#include <joy_common_msgs/msg/joy.hpp>
18#include <rclcpp/rclcpp.hpp>
19#include <std_msgs/msg/string.hpp>
20#include <timer/timeout.hpp>
21
22namespace behavior_tree
23{
24
30class UpdateMode : public BT::SyncActionNode
31{
32public:
41 const std::string & name, const BT::NodeConfig & config,
42 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub,
43 rclcpp::Node::SharedPtr ros_node, uint64_t timeout_ms);
44
53 static BT::PortsList providedPorts();
54
60 BT::NodeStatus tick() override;
61
62private:
68 bool _check_value(std::variant<bool, double> value);
69
70 rclcpp::Node::SharedPtr ros_node_;
71 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr logger_pub_;
72 rclcpp::Subscription<joy_common_msgs::msg::Joy>::SharedPtr joy_sub_;
73 joy_common_msgs::msg::Joy::SharedPtr joy_msg_;
74 joy_common::ButtonMap button_map_;
75
76 joy_common::ButtonMap::iterator manual_it, auto_it;
77
78 std::mutex mutex_;
79 std::shared_ptr<timer::Timeout> timeout_;
80 uint64_t timeout_ms_;
81};
82
83} // namespace behavior_tree
84
85#endif // _UPDATE_MODE_HPP
Action node to update the robot's operation mode based on Joystick input.
Definition: update_mode.hpp:31
BT::NodeStatus tick() override
Checks joystick state and updates the mode.
Definition: update_mode.cpp:72
static BT::PortsList providedPorts()
Defines the input and output ports for this node.
Definition: update_mode.cpp:63
joystick library
std::map< std::string, std::function< ButtonValue(const joy_common_msgs::msg::Buttons &)> > ButtonMap
Definition: joy_common.hpp:24
timeout library