54 const std::string& imarker_name, std::vector<ArmData> arm_datas,
56 : name_(imarker_name), nh_(
"~"), psm_(psm), arm_datas_(arm_datas), color_(color), package_path_(package_path)
59 visual_tools_ = std::make_shared<moveit_visual_tools::MoveItVisualTools>(
70 const std::string imarker_topic =
nh_.
getNamespace() +
"/" + imarker_name +
"_imarker";
71 imarker_server_ = std::make_shared<interactive_markers::InteractiveMarkerServer>(imarker_topic,
"",
false);
86 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
90 eef_name = imarker_name +
"_right";
92 eef_name = imarker_name +
"_left";
108 if (!boost::filesystem::exists(file_name))
113 std::ifstream input_file(file_name);
117 if (!std::getline(input_file, line))
141 ee->setIMarkerCallback(callback);
151 ee->setPoseFromRobotState();
158 (*imarker_state_) = scene->getCurrentState();
161 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
170 static const std::size_t MAX_ATTEMPTS = 1000;
171 for (std::size_t attempt = 0; attempt < MAX_ATTEMPTS; ++attempt)
174 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
185 static const bool verbose =
false;
192 if (planning_scene->distanceToCollision(*
imarker_state_) < clearance)
201 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
205 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
248 const std::string& subdirectory)
const 251 namespace fs = boost::filesystem;
255 rootPath = rootPath / fs::path(subdirectory);
257 boost::system::error_code returnedError;
258 fs::create_directories(rootPath, returnedError);
263 ROS_ERROR(
"Unable to create directory %s", subdirectory.c_str());
268 rootPath = rootPath / fs::path(file_name);
269 file_path = rootPath.string();
277 std::vector<std::string> tips;
278 for (std::size_t i = 0; i <
arm_datas_.size(); ++i)
279 tips.push_back(
arm_datas_[i].ee_link_->getName());
283 const std::size_t attempts = 10;
284 const double timeout = 1.0 / 30.0;
290 bool collision_checking_verbose_ =
false;
291 bool only_check_self_collision_ =
false;
295 boost::scoped_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
297 constraint_fn = boost::bind(&isIKStateValid, static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get(),
298 collision_checking_verbose_, only_check_self_collision_,
visual_tools_, _1, _2, _3);
302 std::size_t outer_attempts = 20;
303 for (std::size_t i = 0; i < outer_attempts; ++i)
305 if (!
imarker_state_->setFromIK(group, poses, tips, attempts, timeout, constraint_fn))
321 ee->setPoseFromRobotState();
346 const std::size_t num_collision_objects = planning_scene->
getCollisionWorld()->getWorld()->size();
347 if (num_collision_objects == 0)
349 ROS_ERROR_STREAM_NAMED(
"imarker_robot_state",
"No collision objects exist in world, you need at least a table " 350 "modeled for the controller to work");
351 ROS_ERROR_STREAM_NAMED(
"imarker_robot_state",
"To fix this, relaunch the teleop/head tracking/whatever MoveIt! " 352 "node to publish the collision objects");
362 if (only_check_self_collision)
382 visual_tools->publishContactPoints(*robot_state, planning_scene);
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
void robotStateToStream(const RobotState &state, std::ostream &out, bool include_header=true, const std::string &separator=",")
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
const std::string & getName() const
#define ROS_INFO_STREAM_NAMED(name, args)
void update(bool force=false)
#define ROS_WARN_STREAM_THROTTLE_NAMED(period, name, args)
const std::string & getNamespace() const
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
void streamToRobotState(RobotState &state, const std::string &line, const std::string &separator=",")
boost::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
bool isStateColliding(const std::string &group="", bool verbose=false)
const collision_detection::CollisionWorldConstPtr & getCollisionWorld() const
#define ROS_WARN_STREAM_NAMED(name, args)