Skip to content
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

Try fix robot start state with STOMP #26

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 4 additions & 5 deletions stomp_moveit/src/stomp_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -267,7 +267,7 @@ bool StompPlanner::solve(planning_interface::MotionPlanDetailedResponse &res)
}

// creating request response
moveit::core::RobotState robot_state(robot_model_);
moveit::core::RobotState robot_state = planning_scene_->getCurrentState();
moveit::core::robotStateMsgToRobotState(request_.start_state,robot_state);
res.trajectory_[0]= robot_trajectory::RobotTrajectoryPtr(new robot_trajectory::RobotTrajectory(
robot_model_,group_));
Expand Down Expand Up @@ -328,7 +328,7 @@ bool StompPlanner::getSeedParameters(Eigen::MatrixXd& parameters) const
* Validating seed trajectory by ensuring that it does obey the
* motion plan request constraints
*/
moveit::core::RobotState state (robot_model_);
moveit::core::RobotState state = planning_scene_->getCurrentState();
const auto* group = state.getJointModelGroup(group_);
const auto& joint_names = group->getActiveJointModelNames();
const auto& tool_link = group->getLinkModelNames().back();
Expand Down Expand Up @@ -471,7 +471,7 @@ bool StompPlanner::parametersToJointTrajectory(const Eigen::MatrixXd& parameters

trajectory_processing::IterativeParabolicTimeParameterization time_generator;
robot_trajectory::RobotTrajectory traj(robot_model_,group_);
moveit::core::RobotState robot_state(robot_model_);
moveit::core::RobotState robot_state = planning_scene_->getCurrentState();
if(!moveit::core::robotStateMsgToRobotState(request_.start_state,robot_state))
{
return false;
Expand Down Expand Up @@ -587,15 +587,14 @@ bool StompPlanner::getStartAndGoal(Eigen::VectorXd& start, Eigen::VectorXd& goal
using namespace moveit::core;
using namespace utils::kinematics;

RobotStatePtr state(new RobotState(robot_model_));
RobotStatePtr state(new RobotState(planning_scene_->getCurrentState()));
const JointModelGroup* joint_group = robot_model_->getJointModelGroup(group_);
std::string tool_link = joint_group->getLinkModelNames().back();
bool found_goal = false;

try
{
// copying start state
state->setToDefaultValues();
if(!robotStateMsgToRobotState(request_.start_state,*state))
{
ROS_ERROR("%s Failed to extract start state from MotionPlanRequest",getName().c_str());
Expand Down