15#include "auto_apms_behavior_tree_core/node.hpp"
16#include "pyrobosim_msgs/msg/robot_state.hpp"
18#define INPUT_KEY_ROBOT "robot"
19#define OUTPUT_KEY_LOCATION "location"
20#define OUTPUT_KEY_BATTERY "battery"
22namespace auto_apms_simulation
25class GetRobotState :
public auto_apms_behavior_tree::core::RosSubscriberNode<pyrobosim_msgs::msg::RobotState>
27 bool first_message_received_ =
false;
28 MessageType last_msg_;
31 GetRobotState(
const std::string & instance_name,
const Config & config, Context context)
36 static BT::PortsList providedPorts()
39 BT::OutputPort<double>(OUTPUT_KEY_BATTERY,
"{=}",
"Current battery state [%]."),
40 BT::OutputPort<std::string>(OUTPUT_KEY_LOCATION,
"{=}",
"Current location name."),
41 BT::InputPort<std::string>(INPUT_KEY_ROBOT,
"Name of the robot.")};
44 BT::NodeStatus onTick(
const std::shared_ptr<MessageType> & last_msg_ptr)
final
48 first_message_received_ =
true;
49 last_msg_ = *last_msg_ptr;
52 if (!first_message_received_)
return BT::NodeStatus::FAILURE;
54 setOutput(OUTPUT_KEY_LOCATION, last_msg_.last_visited_location);
55 setOutput(OUTPUT_KEY_BATTERY, last_msg_.battery_level);
56 return BT::NodeStatus::SUCCESS;
RosSubscriberNode(const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
#define AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(type)
Macro for registering a behavior tree node plugin.