berkeleyauv / behavior_tree

ROS2 package for managing the AUV's behavior using BTCPP behavior trees.
10 stars 2 forks source link

Strange behavior when using your own node #1

Closed solid-sinusoid closed 2 years ago

solid-sinusoid commented 2 years ago

Hi guys, really liked your package. I'm trying to use it to control my robot. At the moment I am implementing the simplest behavior tree with at least one node of the behavior tree. But I'm getting a weird error. If you go into background, then I have implemented a simple client for a service that will request the position of a specific part in Gazebo, but then I saw your package and decided to simplify the code a bit using your package.

More specifically about the error. I don't think it's entirely due to your package, because the code looks logical and correct.

Here is the complete code of what I am trying to do with your package

Code ```cpp #include "gazebo_msgs/srv/get_entity_state.hpp" #include "behaviortree_cpp_v3/bt_factory.h" #include "behavior_tree/BtService.hpp" using namespace BT; using GetEntityStateSrv = gazebo_msgs::srv::GetEntityState; class GetEntityState : public BtService { public: GetEntityState(const std::string & name, const BT::NodeConfiguration & config) : BtService(name, config){} GetEntityStateSrv::Request::SharedPtr populate_request() override { std::string entity_name; getInput("PartName", entity_name); RCLCPP_INFO(_node->get_logger(), "Provided part name [%s]", entity_name.c_str()); GetEntityStateSrv::Request::SharedPtr request; //RCLCPP_INFO(_node->get_logger(), "Populate request"); request->name = entity_name; //request->set__name(entity_name); //RCLCPP_INFO(_node->get_logger(), "Get request [%s]", request->name.c_str()); RCLCPP_INFO(_node->get_logger(), "Populate request"); return request; } BT::NodeStatus handle_response(GetEntityStateSrv::Response::SharedPtr response) override { RCLCPP_INFO(_node->get_logger(), "Service call complete"); return BT::NodeStatus::SUCCESS; } static PortsList providedPorts() { return providedBasicPorts({ InputPort("PartName")}); } private: std::string part_name_; }; BT_REGISTER_NODES(factory) { factory.registerNodeType("GetEntityState"); } ```

After running bt_engine I get the following output with ERROR

Output ``` [INFO] [launch]: All log files can be found below /home/bill-finger/.ros/log/2022-02-02-19-05-31-151990-billfinger-pc-68478 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [bt_check-1]: process started with pid [68482] [bt_check-1] [INFO] [1643814331.291864104] [bt_engine]: Loading plugin: librobossembler_get_entity_state_bt_action_client.so [bt_check-1] [INFO] [1643814331.307614503] [bt_engine]: Loading tree from file: /home/bill-finger/rasms_ws/install/share/robossembler/behavior_trees_xml/atomic_skills_xml/simple_sequence.xml [bt_check-1] [INFO] [1643814331.309886762] [bt_node]: Service client created for /get_entity_state with timeout 10ms [bt_check-1] [INFO] [1643814331.309992090] [bt_engine]: Groot monitoring enabled with server port [1667] and publisher port [1666] [bt_check-1] [INFO] [1643814331.310767528] [bt_engine]: Running tree at frequency 10Hz [bt_check-1] [INFO] [1643814331.310908514] [bt_node]: Provided part name [rasmt] [ERROR] [bt_check-1]: process has died [pid 68482, exit code -11, cmd '/home/bill-finger/rasms_ws/install/lib/robossembler/bt_check --ros-args -r __ns:=/ --params-file /tmp/launch_params_ciuhm4_h --params-file /tmp/launch_params_ifepcymy']. ```

As you can see, the request initializes fine, but the assignment causes problems.

Here is my xml file

XML ```xml ```

Can you recommend me something to fix this error?

solid-sinusoid commented 2 years ago

I forgot to add that I wrote a client for a service before that worked perfectly. Here is an example code that worked for me:

Worked code ```cpp #include #include #include #include #include #include #include "robot_bt/behavior_tree_nodes/atomic_skills/EmuPoseEstimation.hpp" namespace task_planner { static const rclcpp::Logger LOGGER = rclcpp::get_logger("PartPoseEstimation"); EmuPoseEstimation::EmuPoseEstimation(const std::string &xml_tag_name, const BT::NodeConfiguration &conf) : ActionNodeBase(xml_tag_name, conf) { rclcpp::Node::SharedPtr node; config().blackboard->get("node", node); RCLCPP_INFO(LOGGER, "EmuPoseEstimation constructor started"); } void EmuPoseEstimation::halt() { _halt_request = true; RCLCPP_INFO(LOGGER,"EmuPoseEstimation halt"); } BT::NodeStatus EmuPoseEstimation::tick() { rclcpp::Node::SharedPtr gz_get_entity_state; config().blackboard->get("node", gz_get_entity_state); RCLCPP_INFO(LOGGER, "EmuPoseEstimation action started"); rclcpp::Client::SharedPtr client = gz_get_entity_state->create_client ("/get_entity_state"); rclcpp::executors::SingleThreadedExecutor executor; executor.add_node(gz_get_entity_state); std::thread([&executor]() {executor.spin();}).detach(); std::string gazebo_model_name; getInput("PartName",gazebo_model_name); if(std::find(available_model_name_.begin(), available_model_name_.end(), gazebo_model_name) != available_model_name_.end()) { model_name_=gazebo_model_name; RCLCPP_INFO(LOGGER, "Provided model name [%s]", gazebo_model_name.c_str()); }else{ RCLCPP_WARN(LOGGER,"Provided not allowed model name [%s]", gazebo_model_name.c_str()); } auto request = std::make_shared(); request->name=model_name_; RCLCPP_INFO(LOGGER, "Provided service call with model name [%s]", request->name.c_str()); while (!client->wait_for_service(std::chrono::seconds(1))) { if (!rclcpp::ok()) { RCLCPP_ERROR(LOGGER, "Interruped while waiting for the server."); return BT::NodeStatus::FAILURE; } RCLCPP_INFO(LOGGER, "Server not available, waiting again..."); } auto result = client->async_send_request(request); RCLCPP_INFO(LOGGER, "Get Pose x = %f y = %f z = %f", result.get()->state.pose.position.x, result.get()->state.pose.position.y, result.get()->state.pose.position.z); return BT::NodeStatus::SUCCESS; } } #include "behaviortree_cpp_v3/bt_factory.h" BT_REGISTER_NODES(factory) { factory.registerNodeType("EmuPoseEstimation"); } ```
solid-sinusoid commented 2 years ago

Solved using

auto request = std::make_shared<GetEntityStateSrv::Request>();