update main
This commit is contained in:
parent
d5e7768d90
commit
e8ea09e020
20 changed files with 315 additions and 168 deletions
|
@ -14,19 +14,19 @@
|
|||
<Sequence>
|
||||
<Action ID="MoveToPoseArray" cancel_timeout="5000" pose_vec_in="{goal_pose}"
|
||||
pose_vec_out="{goal_pose}"
|
||||
robot_name="{robot_name}" server_name="/move_topose" server_timeout="5000" />
|
||||
robot_name="{robot_name}" server_name="/cartesian_move_to_pose" server_timeout="5000" />
|
||||
<Action ID="MoveToPoseArray" cancel_timeout="5000" pose_vec_in="{goal_pose}"
|
||||
pose_vec_out="{goal_pose}"
|
||||
robot_name="{robot_name}" server_name="/move_cartesian" server_timeout="5000" />
|
||||
robot_name="{robot_name}" server_name="/cartesian_move_to_pose" server_timeout="5000" />
|
||||
<Action ID="MoveToPoseArray" cancel_timeout="5000" pose_vec_in="{goal_pose}"
|
||||
pose_vec_out="{goal_pose}"
|
||||
robot_name="{robot_name}" server_name="/move_cartesian" server_timeout="5000" />
|
||||
robot_name="{robot_name}" server_name="/cartesian_move_to_pose" server_timeout="5000" />
|
||||
<Action ID="MoveToPoseArray" cancel_timeout="5000" pose_vec_in="{goal_pose}"
|
||||
pose_vec_out="{goal_pose}"
|
||||
robot_name="{robot_name}" server_name="/move_cartesian" server_timeout="5000" />
|
||||
robot_name="{robot_name}" server_name="/cartesian_move_to_pose" server_timeout="5000" />
|
||||
<Action ID="MoveToPoseArray" cancel_timeout="5000" pose_vec_in="{goal_pose}"
|
||||
pose_vec_out="{goal_pose}"
|
||||
robot_name="{robot_name}" server_name="/move_cartesian" server_timeout="5000" />
|
||||
robot_name="{robot_name}" server_name="/cartesian_move_to_pose" server_timeout="5000" />
|
||||
|
||||
</Sequence>
|
||||
</BehaviorTree>
|
||||
|
|
|
@ -27,11 +27,16 @@ def generate_launch_description():
|
|||
Node(
|
||||
package='behavior_tree',
|
||||
executable='bt_engine',
|
||||
# prefix=['gdbserver localhost:3000'],
|
||||
# prefix=['gdbserver localhost:1234'],
|
||||
parameters=[
|
||||
btfile_param,
|
||||
bt_skills_param
|
||||
]
|
||||
bt_skills_param,
|
||||
{'use_sim_time': True}
|
||||
],
|
||||
# arguments=[
|
||||
# "--ros-args",
|
||||
# "--log-level", "debug",
|
||||
# ],
|
||||
)
|
||||
]
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@ public:
|
|||
if (response->ok) {
|
||||
// TODO We need better perfomance for call it in another place for all BT nodes
|
||||
// - Make it via shared_ptr forward throught blackboard
|
||||
auto t = std::make_shared<rbs_utils::AssemblyConfigLoader>("asp-example2", _node);
|
||||
auto t = std::make_shared<rbs_utils::AssemblyConfigLoader>("asp-example", _node);
|
||||
auto p = t->getWorkspaceInspectorTrajectory();
|
||||
setOutput("workspace", p);
|
||||
return BT::NodeStatus::SUCCESS;
|
||||
|
|
|
@ -29,8 +29,8 @@ class MoveToPose : public BtAction<MoveToPoseAction> {
|
|||
|
||||
goal.robot_name = robot_name_;
|
||||
goal.target_pose = pose_des;
|
||||
goal.end_effector_acceleration = 0.5;
|
||||
goal.end_effector_velocity = 0.5;
|
||||
goal.end_effector_acceleration = 1.0;
|
||||
goal.end_effector_velocity = 1.0;
|
||||
|
||||
RCLCPP_INFO(_node->get_logger(), "Goal populated");
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue