Skip to content

Commit

Permalink
Update to later moveit2 version
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed May 3, 2023
1 parent 609fc20 commit eaa3701
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 15 deletions.
16 changes: 8 additions & 8 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,13 +144,13 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
state = scene->getCurrentState();
}

plan.plan_components_.reserve(solution.sub_trajectory.size());
plan.plan_components.reserve(solution.sub_trajectory.size());
auto make_executable_trajectory =
[&](const moveit_task_constructor_msgs::msg::SubTrajectory& sub_traj, const std::string& description,
const std::function<bool(const plan_execution::ExecutableMotionPlan*)>& on_success_callback) {
plan.plan_components_.emplace_back();
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components_.back();
exec_traj.description_ = description;
plan.plan_components.emplace_back();
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components.back();
exec_traj.description = description;
const moveit::core::JointModelGroup* group = nullptr;
{
std::vector<std::string> joint_names(sub_traj.trajectory.joint_trajectory.joint_names);
Expand All @@ -166,12 +166,12 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
RCLCPP_DEBUG(LOGGER, "Using JointModelGroup '%s' for execution", group->getName().c_str());
}
}
exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
exec_traj.trajectory_->setRobotTrajectoryMsg(state, sub_traj.trajectory);
exec_traj.controller_names_ = sub_traj.execution_info.controller_names;
exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
exec_traj.trajectory->setRobotTrajectoryMsg(state, sub_traj.trajectory);
exec_traj.controller_name = sub_traj.execution_info.controller_names;

/* todo add action feedback and markers */
exec_traj.effect_on_success_ = on_success_callback;
exec_traj.effect_on_success = on_success_callback;
return true;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ class GenerateRandomPose : public GeneratePose
* PoseDimension (X/Y/Z/ROLL/PITCH/YAW) for randomizing the pose.
* The distribution_param is applied to the specified distribution method while the target pose value is used as
* seed. The order in which the PoseDimension samplers are specified matters as the samplers are applied in sequence.
* That way it's possible to implement different Euler angles (i.e. XYZ, ZXZ, YXY) or even construct more complex
* sampling regions by applying translations after rotations.
* That way it's possible to implement different Euler angles (i.e. XYZ, ZXZ, YXY) or even construct more complex
* sampling regions by applying translations after rotations.
* Currently supported distributions are:
* * std::uniform_real_distrubtion: distribution_param specifies the full value range around the target_pose value
* * std::normal_distribution: distribution_param is used as stddev, target_pose value is mean
Expand Down
9 changes: 4 additions & 5 deletions core/src/stages/connect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,11 +164,10 @@ void Connect::compute(const InterfaceState& from, const InterfaceState& to) {

// Do not push partial solutions
if (success) {
sub_trajectories.push_back(trajectory);
}
else {
// Pushing a nullptr instead of a failed trajectory.
sub_trajectories.push_back(nullptr);
sub_trajectories.push_back(trajectory);
} else {
// Pushing a nullptr instead of a failed trajectory.
sub_trajectories.push_back(nullptr);
}

if (!success)
Expand Down

0 comments on commit eaa3701

Please sign in to comment.