void scanCallback(const crl::multisense::lidar::Header& iHeader) { int64_t startAbsoluteUtime = iHeader.timeStartSeconds*1e6 + iHeader.timeStartMicroSeconds; int64_t endAbsoluteUtime = iHeader.timeEndSeconds*1e6 + iHeader.timeEndMicroSeconds; double scanTime = (endAbsoluteUtime - startAbsoluteUtime)*1e-6; // in sec double angleDiff = 1e-6*(iHeader.spindleAngleEnd-iHeader.spindleAngleStart); if (angleDiff < -kPi) angleDiff += 2*kPi; else if (angleDiff > kPi) angleDiff -= 2*kPi; const double velocity = angleDiff / scanTime; // publish joint state for beginning and end of scan publishJointState(startAbsoluteUtime, iHeader.spindleAngleStart, velocity); publishJointState(endAbsoluteUtime, iHeader.spindleAngleEnd, velocity); // publish laser scan data const double arcRadians = 1e-6*iHeader.scanArc; multisense::planar_lidar_t msg; msg.utime = endAbsoluteUtime; // was startAbsoluteUtime until 04-2014 msg.ranges.resize(iHeader.pointCount); msg.intensities.resize(iHeader.pointCount); for (size_t i = 0; i < iHeader.pointCount; ++i) { msg.ranges[i] = iHeader.rangesP[i] / 1000.0f; // millimeters to meters msg.intensities[i] = iHeader.intensitiesP[i]; // in device units } msg.nranges = msg.ranges.size(); msg.nintensities = msg.intensities.size(); msg.rad0 = -arcRadians / 2.0; msg.radstep = arcRadians / (iHeader.pointCount - 1); mLaser->mPublishLcm->publish(mLaser->mOutputChannel, &msg); }
void spin() { // initialize random seed srand(time(NULL)); // dynamics model boost::shared_ptr<DynamicModel > dyn_model( new DynModelPlanar5() ); std::string robot_description_str; std::string robot_semantic_description_str; nh_.getParam("/robot_description", robot_description_str); nh_.getParam("/robot_semantic_description", robot_semantic_description_str); // // collision model // boost::shared_ptr<self_collision::CollisionModel> col_model = self_collision::CollisionModel::parseURDF(robot_description_str); col_model->parseSRDF(robot_semantic_description_str); col_model->generateCollisionPairs(); // external collision objects - part of virtual link connected to the base link self_collision::Link::VecPtrCollision col_array; col_array.push_back( self_collision::createCollisionCapsule(0.2, 0.3, KDL::Frame(KDL::Rotation::RotX(90.0/180.0*PI), KDL::Vector(1, 0.5, 0))) ); if (!col_model->addLink("env_link", "base", col_array)) { ROS_ERROR("ERROR: could not add external collision objects to the collision model"); return; } col_model->generateCollisionPairs(); // // robot state // std::vector<std::string > joint_names; joint_names.push_back("0_joint"); joint_names.push_back("1_joint"); joint_names.push_back("2_joint"); joint_names.push_back("3_joint"); joint_names.push_back("4_joint"); int ndof = joint_names.size(); Eigen::VectorXd q, dq, ddq, torque; q.resize( ndof ); dq.resize( ndof ); ddq.resize( ndof ); torque.resize( ndof ); for (int q_idx = 0; q_idx < ndof; q_idx++) { q[q_idx] = -0.1; dq[q_idx] = 0.0; ddq[q_idx] = 0.0; torque[q_idx] = 0.0; } std::string effector_name = "effector"; int effector_idx = col_model->getLinkIndex(effector_name); // // kinematic model // boost::shared_ptr<KinematicModel> kin_model( new KinematicModel(robot_description_str, joint_names) ); KinematicModel::Jacobian J_r_HAND_6, J_r_HAND; J_r_HAND_6.resize(6, ndof); J_r_HAND.resize(3, ndof); std::vector<KDL::Frame > links_fk(col_model->getLinksCount()); // joint limits Eigen::VectorXd lower_limit(ndof), upper_limit(ndof), limit_range(ndof), max_trq(ndof); int q_idx = 0; for (std::vector<std::string >::const_iterator name_it = joint_names.begin(); name_it != joint_names.end(); name_it++, q_idx++) { lower_limit[q_idx] = kin_model->getLowerLimit(q_idx); upper_limit[q_idx] = kin_model->getUpperLimit(q_idx); limit_range[q_idx] = 10.0/180.0*PI; max_trq[q_idx] = 10.0; } Eigen::VectorXd max_q(ndof); max_q(0) = 10.0/180.0*PI; max_q(1) = 20.0/180.0*PI; max_q(2) = 20.0/180.0*PI; max_q(3) = 30.0/180.0*PI; max_q(4) = 40.0/180.0*PI; boost::shared_ptr<DynamicsSimulatorHandPose> sim( new DynamicsSimulatorHandPose(ndof, 6, effector_name, col_model, kin_model, dyn_model, joint_names, max_q) ); /* // // Tasks declaration // Task_JLC task_JLC(lower_limit, upper_limit, limit_range, max_trq); Task_WCC task_WCC(ndof, 3, 4); double activation_dist = 0.05; Task_COL task_COL(ndof, activation_dist, 10.0, kin_model, col_model); Task_HAND task_HAND(ndof, 3); */ /* while (ros::ok()) { // // wrist collision constraint // Eigen::VectorXd torque_WCC(ndof); Eigen::MatrixXd N_WCC(ndof, ndof); task_WCC.compute(q, dq, dyn_model->getM(), dyn_model->getInvM(), torque_WCC, N_WCC, markers_pub_); markers_pub_.publish(); ros::spinOnce(); char ch = getchar(); if (ch == 'a') { q(3) -= 0.1; } else if (ch == 'd') { q(3) += 0.1; } else if (ch == 's') { q(4) -= 0.1; } else if (ch == 'w') { q(4) += 0.1; } } return; */ // loop variables ros::Time last_time = ros::Time::now(); KDL::Frame r_HAND_target; int loop_counter = 10000; ros::Rate loop_rate(100); while (true) { generatePossiblePose(r_HAND_target, q, ndof, effector_name, col_model, kin_model); sim->setState(q, dq, ddq); sim->setTarget(r_HAND_target); sim->oneStep(); if (!sim->inCollision()) { break; } } while (ros::ok()) { if (loop_counter > 500) { Eigen::VectorXd q_tmp(ndof); generatePossiblePose(r_HAND_target, q_tmp, ndof, effector_name, col_model, kin_model); sim->setTarget(r_HAND_target); publishTransform(br, r_HAND_target, "effector_dest", "base"); loop_counter = 0; } loop_counter += 1; sim->oneStep(&markers_pub_, 3000); /* if (sim->inCollision() && !collision_in_prev_step) { collision_in_prev_step = true; std::cout << "collision begin" << std::endl; } else if (!sim->inCollision() && collision_in_prev_step) { collision_in_prev_step = false; std::cout << "collision end" << std::endl; } */ sim->getState(q, dq, ddq); // publish markers and robot state with limited rate ros::Duration time_elapsed = ros::Time::now() - last_time; if (time_elapsed.toSec() > 0.05) { // calculate forward kinematics for all links for (int l_idx = 0; l_idx < col_model->getLinksCount(); l_idx++) { kin_model->calculateFk(links_fk[l_idx], col_model->getLinkName(l_idx), q); } publishJointState(joint_state_pub_, q, joint_names); int m_id = 0; m_id = addRobotModelVis(markers_pub_, m_id, col_model, links_fk); markers_pub_.publish(); ros::Time last_time = ros::Time::now(); } ros::spinOnce(); loop_rate.sleep(); } }