Skip to content

Add trajectory pausable behaviour #7

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: main
Choose a base branch
from

Conversation

MikeWrock
Copy link

@MikeWrock MikeWrock commented May 5, 2025

Use this objective to test in lab_sim:

<?xml version='1.0' encoding='UTF-8'?>
<root BTCPP_format="4" main_tree_to_execute="Test Pause Resume">
  <!--//////////-->
  <BehaviorTree ID="Test Pause Resume" _description="" _favorite="false">
    <Control ID="Sequence" name="TopLevelSequence">
      <SubTree ID="Move to Waypoint" _collapsed="true" acceleration_scale_factor="1.0" controller_action_server="/joint_trajectory_controller/follow_joint_trajectory" controller_names="/joint_trajectory_controller" joint_group_name="manipulator" keep_orientation="false" keep_orientation_tolerance="0.05" link_padding="0.01" seed="0" velocity_scale_factor="1.0" waypoint_name="Beaker 1d - Place"/>
      <Action ID="RetrieveWaypoint" waypoint_joint_state="{target_joint_state}" waypoint_name="Beaker 1a - Pre Pick" joint_group_name="manipulator"/>
      <Action ID="ActivateControllers" controller_names="/joint_trajectory_controller"/>
      <Action ID="PlanToJointGoal" joint_goal="{target_joint_state}" keep_orientation_tolerance="1.0" keep_orientation="false" acceleration_scale_factor="1.0" velocity_scale_factor="0.1" planning_group_name="manipulator" seed="100" joint_trajectory_msg="{joint_trajectory_msg}" keep_orientation_link_names="grasp_link" max_iterations="5000" trajectory_sampling_rate="100" link_padding="0.0"/>
      <Control ID="Fallback">
        <Action ID="ExecuteAndTrackJointTrajectory" action_name="/joint_trajectory_controller/follow_joint_trajectory" joint_trajectory_msg="{joint_trajectory_msg}" time_from_start="{time_from_start}" trajectory_remainder="{joint_trajectory_remainder}"/>
        <Decorator ID="RetryUntilSuccessful" num_attempts="-1">
          <Control ID="Sequence">
            <SubTree ID="Move to Waypoint" _collapsed="true" acceleration_scale_factor="1.0" controller_action_server="/joint_trajectory_controller/follow_joint_trajectory" controller_names="/joint_trajectory_controller" joint_group_name="manipulator" keep_orientation="false" keep_orientation_tolerance="0.05" link_padding="0.01" seed="0" velocity_scale_factor="1.0" waypoint_name="Beaker 1d - Place"/>
            <Action ID="BreakpointSubscriber" breakpoint_topic="/moveit_pro_breakpoint"/>
            <Action ID="GetTrajectoryStateAtTime" from_start="true" joint_state="{joint_state}" joint_trajectory_msg="{joint_trajectory_remainder}" time_from_reference="0.000000"/>
            <SubTree ID="Move to Joint State" _collapsed="true" acceleration_scale_factor="1.0" controller_action_server="/joint_trajectory_controller/follow_joint_trajectory" controller_names="joint_trajectory_controller" joint_group_name="manipulator" keep_orientation="false" keep_orientation_tolerance="0.05" link_padding="0.01" seed="0" target_joint_state="{joint_state}" velocity_scale_factor="1.0"/>
            <Action ID="BreakpointSubscriber" breakpoint_topic="/moveit_pro_breakpoint"/>
            <Action ID="ExecuteAndTrackJointTrajectory" action_name="/joint_trajectory_controller/follow_joint_trajectory" joint_trajectory_msg="{joint_trajectory_remainder}" time_from_start="{time_from_start}" trajectory_remainder="{joint_trajectory_remainder}"/>
          </Control>
        </Decorator>
      </Control>
    </Control>
  </BehaviorTree>
  <TreeNodesModel>
    <SubTree ID="Test Pause Resume">
      <MetadataFields>
        <Metadata runnable="true"/>
        <Metadata subcategory="AAA"/>
      </MetadataFields>
    </SubTree>
  </TreeNodesModel>
</root>

And call ros2 service call /pause_trajectory std_srvs/srv/Trigger during playback (see video)

screencap-2025-05-05_07.12.04.mp4

@MikeWrock MikeWrock requested a review from bgill92 May 5, 2025 13:37
@MikeWrock MikeWrock force-pushed the trajectory-remainder branch from 372f2b8 to c1d00f0 Compare May 5, 2025 13:40
@MikeWrock MikeWrock force-pushed the trajectory-remainder branch from c1d00f0 to c535c9b Compare May 5, 2025 14:09
Copy link

@bgill92 bgill92 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

First pass

goal.goal_time_tolerance = rclcpp::Duration::from_seconds(time_tolerance);

// Send goal with feedback callback
typename rclcpp_action::Client<FollowJointTrajectory>::SendGoalOptions options;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is this typename? That shouldn't be needed.

}
catch (const rclcpp_action::exceptions::UnknownGoalHandleError& e)
{
RCLCPP_WARN(rclcpp::get_logger("ExecuteAndTrackJointTrajectory"), "Failed to cancel goal: %s", e.what());
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should probably be an error if we can't pause the joint trajectory?

const std::shared_ptr<const FollowJointTrajectory::Feedback> feedback)
{
last_feedback_time_ = feedback->desired.time_from_start.sec + feedback->desired.time_from_start.nanosec * 1e-9;
setOutput<double>("time_from_start", last_feedback_time_);
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we have to set time_from_start every time the feedback is processed or only when the trajectory is paused?

Comment on lines +204 to +224
for (; start_index < full_trajectory_.points.size(); ++start_index)
{
double t = full_trajectory_.points[start_index].time_from_start.sec +
full_trajectory_.points[start_index].time_from_start.nanosec * 1e-9;
if (t >= last_feedback_time_)
break;
}
if (start_index >= full_trajectory_.points.size())
return new_traj;

double offset = full_trajectory_.points[start_index].time_from_start.sec +
full_trajectory_.points[start_index].time_from_start.nanosec * 1e-9;
for (size_t i = start_index; i < full_trajectory_.points.size(); ++i)
{
auto pt = full_trajectory_.points[i];
double orig = pt.time_from_start.sec + pt.time_from_start.nanosec * 1e-9;
double adjusted = orig - offset;
pt.time_from_start.sec = static_cast<uint32_t>(adjusted);
pt.time_from_start.nanosec = static_cast<uint32_t>((adjusted - pt.time_from_start.sec) * 1e9);
new_traj.points.push_back(pt);
}
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Some additional here would make this could easier to grok.

@davetcoleman
Copy link
Member

Can we get this month old PR merged in?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants