Skip to content
Snippets Groups Projects
Commit fa74679d authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Updates to new base_bt_client version

parent 3a687c58
No related branches found
No related tags found
No related merge requests found
......@@ -45,8 +45,6 @@ move_pose = gen.add_group("Move arm in cartesian space")
# Name Type Reconfiguration level Description Default Min Max
#gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0)
add_bt_client_params(gen)
gen.add("START", bool_t, 0, "synchronous start", False)
gen.add("RESTART", bool_t, 0, "asynchronous restart of BT", False)
move_joints.add("set_joints", bool_t, 0, "Set selected angles", False)
move_joints.add("torso", double_t, 0, "Target angle for torso", 0.15, 0.0, 0.35)
......
......@@ -50,18 +50,6 @@ void TiagoArmModuleBtClientAlgNode::node_config_update(tiago_arm_module::TiagoAr
std::string move_group;
this->lock();
if(config.START)
{
this->core.start_tree();
config.START=false;
}
if(config.RESTART)
{
this->core.stop_tree();
config.RESTART=false;
}
if (config.set_joints)
{
ROS_WARN("TiagoArmModuleBtClientAlgNode: To change the move_group modify it on module dynamic Reconfigure");
......
......@@ -2,20 +2,40 @@
<root main_tree_to_execute="BehaviorTree">
<!-- ////////// -->
<BehaviorTree ID="BehaviorTree">
<Action ID="NOP"/>
<Action ID="RUNNING"/>
</BehaviorTree>
<!-- ////////// -->
<TreeNodesModel>
<!-- basic_nodes -->
<Action ID="NOP"/>
<Action ID="is_not_start_tree"/>
<Condition ID="async_is_start_tree"/>
<Action ID="is_not_stop_tree"/>
<Condition ID="async_is_stop_tree"/>
<Action ID="set_start_tree"/>
<Action ID="set_stop_tree"/>
<Action ID="reset_start_tree"/>
<Action ID="reset_stop_tree"/>
<Action ID="RUNNING"/>
<Action ID="is_variable_true">
<input_port name="variable"> (bool): Bool variable to check.</input_port>
</Action>
<Action ID="is_variable_false">
<input_port name="variable"> (bool): Bool variable to check.</input_port>
</Action>
<Action ID="transform_pose">
<input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port>
<input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port>
<output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port>
</Action>
<Action ID="compute_distance">
<input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port>
<input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port>
<output_port name="distance"> (double): Distance.</output_port>
</Action>
<Action ID="compare_bigger">
<input_port name="value1"> (double): Value 1.</input_port>
<input_port name="value2"> (double): Value 2.</input_port>
</Action>
<Action ID="compare_smaller">
<input_port name="value1"> (double): Value 1.</input_port>
<input_port name="value2"> (double): Value 2.</input_port>
</Action>
<Action ID="print_msg">
<input_port name="msg"> (std::string): Msg to print.</input_port>
<input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port>
</Action>
<!-- tiago_arm_module -->
<Action ID="sync_cancel_tiago_arm_action"/>
<Action ID="async_cancel_tiago_arm_action"/>
......
......@@ -3,7 +3,6 @@
<!-- ////////// -->
<BehaviorTree ID="BehaviorTree">
<SequenceStar>
<Action ID="async_is_start_tree"/>
<Action ID="set_tiago_arm_move_to_joints_input" target_joints="{target_joints}" joint_tol="{joint_tol}" new_goal="{new_goal}"/>
<Action ID="async_tiago_arm_move_to_joints" target_joints="{target_joints}" joint_tol="{joint_tol}" new_goal="{new_goal}"/>
<Action ID="set_tiago_arm_move_to_pose_input" pose="{pose}" position_tol="{position_tol}" orientation_tol="{orientation_tol}" new_goal="{new_goal}"/>
......@@ -12,16 +11,36 @@
</BehaviorTree>
<!-- ////////// -->
<TreeNodesModel>
<!-- basic_nodes -->
<Action ID="NOP"/>
<Action ID="is_not_start_tree"/>
<Condition ID="async_is_start_tree"/>
<Action ID="is_not_stop_tree"/>
<Condition ID="async_is_stop_tree"/>
<Action ID="set_start_tree"/>
<Action ID="set_stop_tree"/>
<Action ID="reset_start_tree"/>
<Action ID="reset_stop_tree"/>
<!-- basic_nodes -->
<Action ID="RUNNING"/>
<Action ID="is_variable_true">
<input_port name="variable"> (bool): Bool variable to check.</input_port>
</Action>
<Action ID="is_variable_false">
<input_port name="variable"> (bool): Bool variable to check.</input_port>
</Action>
<Action ID="transform_pose">
<input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port>
<input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port>
<output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port>
</Action>
<Action ID="compute_distance">
<input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port>
<input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port>
<output_port name="distance"> (double): Distance.</output_port>
</Action>
<Action ID="compare_bigger">
<input_port name="value1"> (double): Value 1.</input_port>
<input_port name="value2"> (double): Value 2.</input_port>
</Action>
<Action ID="compare_smaller">
<input_port name="value1"> (double): Value 1.</input_port>
<input_port name="value2"> (double): Value 2.</input_port>
</Action>
<Action ID="print_msg">
<input_port name="msg"> (std::string): Msg to print.</input_port>
<input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port>
</Action>
<!-- tiago_arm_module -->
<Action ID="sync_cancel_tiago_arm_action"/>
<Action ID="async_cancel_tiago_arm_action"/>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment