cosmetic fixes

This commit is contained in:
Robert Haschke 2018-02-27 17:22:53 +01:00
parent 2331c9aef2
commit 81d88911a9
4 changed files with 7 additions and 5 deletions

View File

@ -215,8 +215,8 @@ boost::any fromName(const PropertyMap& other, const std::string& other_name)
Property::error::error(const std::string& msg)
: std::runtime_error("Property: " + msg)
, msg_(msg)
: std::runtime_error(msg)
, msg_("Property: " + msg)
{}
void Property::error::setName(const std::string& name)

View File

@ -156,7 +156,7 @@ void ComputeIK::onNewSolution(const SolutionBase &s)
// validate placed link for collisions
bool colliding = isTargetPoseColliding(sandbox_scene, eef_jmg, target_pose, link_name);
if (colliding && !storeFailures()) {
ROS_ERROR("eeg in collision");
ROS_ERROR("eef in collision");
return;
}
@ -174,6 +174,7 @@ void ComputeIK::onNewSolution(const SolutionBase &s)
generateCollisionMarkers(sandbox_state, appender, visualize_links);
std::copy(placed_link_markers.begin(), placed_link_markers.end(), std::back_inserter(solution.markers()));
solution.setCost(std::numeric_limits<double>::infinity()); // mark solution as failure
solution.setName("eef in collision");
spawn(InterfaceState(sandbox_scene), std::move(solution));
return;
} else
@ -260,6 +261,7 @@ void ComputeIK::onNewSolution(const SolutionBase &s)
// mark solution as invalid
solution.setCost(std::numeric_limits<double>::infinity());
solution.setName("no IK found");
// ik target link placement
std::copy(placed_link_markers.begin(), placed_link_markers.end(), std::back_inserter(solution.markers()));

View File

@ -54,7 +54,7 @@ bool FixedState::canCompute() const{
bool FixedState::compute() {
spawn(InterfaceState(scene_), 0.0);
return ran_= true;
return ran_ = true;
}
} } }

View File

@ -65,7 +65,7 @@ SimpleGrasp::SimpleGrasp(const std::string& name)
exposePropertiesOfChild(-1, { "max_ik_solutions", "timeout" });
}
{
auto allow_touch = std::make_unique<ModifyPlanningScene>("enable object collision");
auto allow_touch = std::make_unique<ModifyPlanningScene>("allow object collision");
PropertyMap& p = allow_touch->properties();
p.declare<std::string>("eef");
p.declare<std::string>("object");