| Directory: | ./ |
|---|---|
| File: | src/robot.impl.cc |
| Date: | 2025-05-11 11:10:19 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 123 | 743 | 16.6% |
| Branches: | 142 | 1942 | 7.3% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // Copyright (C) 2009, 2010 by Florent Lamiraux, Thomas Moulard, JRL. | ||
| 2 | // | ||
| 3 | |||
| 4 | // Redistribution and use in source and binary forms, with or without | ||
| 5 | // modification, are permitted provided that the following conditions are | ||
| 6 | // met: | ||
| 7 | // | ||
| 8 | // 1. Redistributions of source code must retain the above copyright | ||
| 9 | // notice, this list of conditions and the following disclaimer. | ||
| 10 | // | ||
| 11 | // 2. Redistributions in binary form must reproduce the above copyright | ||
| 12 | // notice, this list of conditions and the following disclaimer in the | ||
| 13 | // documentation and/or other materials provided with the distribution. | ||
| 14 | // | ||
| 15 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
| 16 | // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
| 17 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR | ||
| 18 | // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT | ||
| 19 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, | ||
| 20 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT | ||
| 21 | // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, | ||
| 22 | // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY | ||
| 23 | // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||
| 24 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
| 25 | // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH | ||
| 26 | // DAMAGE. | ||
| 27 | // | ||
| 28 | // This software is provided "as is" without warranty of any kind, | ||
| 29 | // either expressed or implied, including but not limited to the | ||
| 30 | // implied warranties of fitness for a particular purpose. | ||
| 31 | // | ||
| 32 | // See the COPYING file for more information. | ||
| 33 | |||
| 34 | #include "robot.impl.hh" | ||
| 35 | |||
| 36 | #include <coal/BVH/BVH_model.h> | ||
| 37 | #include <coal/shape/geometric_shapes.h> | ||
| 38 | |||
| 39 | #include <hpp/corbaserver/server-plugin.hh> | ||
| 40 | #include <hpp/core/config-validations.hh> | ||
| 41 | #include <hpp/core/configuration-shooter.hh> | ||
| 42 | #include <hpp/core/distance-between-objects.hh> | ||
| 43 | #include <hpp/core/problem.hh> | ||
| 44 | #include <hpp/core/weighed-distance.hh> | ||
| 45 | #include <hpp/pinocchio/body.hh> | ||
| 46 | #include <hpp/pinocchio/center-of-mass-computation.hh> | ||
| 47 | #include <hpp/pinocchio/collision-object.hh> | ||
| 48 | #include <hpp/pinocchio/configuration.hh> | ||
| 49 | #include <hpp/pinocchio/device.hh> | ||
| 50 | #include <hpp/pinocchio/frame.hh> | ||
| 51 | #include <hpp/pinocchio/fwd.hh> | ||
| 52 | #include <hpp/pinocchio/humanoid-robot.hh> | ||
| 53 | #include <hpp/pinocchio/joint-collection.hh> | ||
| 54 | #include <hpp/pinocchio/joint.hh> | ||
| 55 | #include <hpp/pinocchio/liegroup-element.hh> | ||
| 56 | #include <hpp/pinocchio/liegroup.hh> | ||
| 57 | #include <hpp/pinocchio/urdf/util.hh> | ||
| 58 | #include <hpp/util/debug.hh> | ||
| 59 | #include <hpp/util/exception-factory.hh> | ||
| 60 | #include <iostream> | ||
| 61 | #include <pinocchio/fwd.hpp> | ||
| 62 | #include <pinocchio/multibody/fcl.hpp> | ||
| 63 | #include <pinocchio/multibody/geometry.hpp> | ||
| 64 | #include <pinocchio/multibody/model.hpp> | ||
| 65 | |||
| 66 | #include "hpp/pinocchio_idl/robots-fwd.hh" | ||
| 67 | #include "tools.hh" | ||
| 68 | |||
| 69 | namespace hpp { | ||
| 70 | namespace corbaServer { | ||
| 71 | namespace impl { | ||
| 72 | using pinocchio::Data; | ||
| 73 | using pinocchio::FrameIndex; | ||
| 74 | using pinocchio::JointIndex; | ||
| 75 | using pinocchio::Model; | ||
| 76 | |||
| 77 | namespace { | ||
| 78 | using CORBA::Long; | ||
| 79 | using CORBA::ULong; | ||
| 80 | const ::pinocchio::FrameType JOINT_FRAME = | ||
| 81 | (::pinocchio::FrameType)(::pinocchio::JOINT | ::pinocchio::FIXED_JOINT); | ||
| 82 | |||
| 83 | ✗ | static void localSetJointBounds(const JointPtr_t& joint, vector_t jointBounds) { | |
| 84 | static const value_type inf = std::numeric_limits<value_type>::infinity(); | ||
| 85 | ✗ | if (jointBounds.size() % 2 == 1) { | |
| 86 | ✗ | HPP_THROW(std::invalid_argument, "Expect a vector of even size"); | |
| 87 | } | ||
| 88 | ✗ | for (std::size_t i = 0; i < (std::size_t)jointBounds.size() / 2; i++) { | |
| 89 | ✗ | value_type& vMin = jointBounds[2 * i]; | |
| 90 | ✗ | value_type& vMax = jointBounds[2 * i + 1]; | |
| 91 | ✗ | if (vMin > vMax) { | |
| 92 | ✗ | vMin = -inf; | |
| 93 | ✗ | vMax = inf; | |
| 94 | } | ||
| 95 | } | ||
| 96 | Eigen::Map<vector_t, Eigen::Unaligned, Eigen::InnerStride<2> > lower( | ||
| 97 | ✗ | &jointBounds[0], (jointBounds.size() + 1) / 2); | |
| 98 | Eigen::Map<vector_t, Eigen::Unaligned, Eigen::InnerStride<2> > upper( | ||
| 99 | ✗ | &jointBounds[1], (jointBounds.size()) / 2); | |
| 100 | ✗ | joint->lowerBounds(lower); | |
| 101 | ✗ | joint->upperBounds(upper); | |
| 102 | } | ||
| 103 | |||
| 104 | ✗ | static floatSeq* localGetJointBounds(const JointPtr_t& joint) { | |
| 105 | ✗ | std::size_t jointNbDofs = joint->configSize(); | |
| 106 | ✗ | floatSeq* ret = new floatSeq; | |
| 107 | ✗ | ret->length((ULong)(2 * jointNbDofs)); | |
| 108 | ✗ | for (std::size_t iDof = 0; iDof < jointNbDofs; iDof++) { | |
| 109 | ✗ | if (joint->isBounded(iDof)) { | |
| 110 | ✗ | (*ret)[(ULong)(2 * iDof)] = joint->lowerBound(iDof); | |
| 111 | ✗ | (*ret)[(ULong)(2 * iDof + 1)] = joint->upperBound(iDof); | |
| 112 | } else { | ||
| 113 | ✗ | (*ret)[(ULong)(2 * iDof)] = 1; | |
| 114 | ✗ | (*ret)[(ULong)(2 * iDof + 1)] = 0; | |
| 115 | } | ||
| 116 | } | ||
| 117 | ✗ | return ret; | |
| 118 | } | ||
| 119 | } // end of namespace. | ||
| 120 | |||
| 121 | // -------------------------------------------------------------------- | ||
| 122 | |||
| 123 |
1/2✓ Branch 3 taken 8 times.
✗ Branch 4 not taken.
|
16 | Robot::Robot() : server_(NULL) {} |
| 124 | |||
| 125 | // -------------------------------------------------------------------- | ||
| 126 | |||
| 127 | 98 | core::ProblemSolverPtr_t Robot::problemSolver() { | |
| 128 | 98 | return server_->problemSolver(); | |
| 129 | } | ||
| 130 | |||
| 131 | // -------------------------------------------------------------------- | ||
| 132 | |||
| 133 | 6 | void Robot::createRobot(const char* inRobotName) { | |
| 134 |
1/2✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
|
6 | std::string robotName(inRobotName); |
| 135 |
2/4✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
|
6 | DevicePtr_t robot(problemSolver()->createRobot(robotName)); |
| 136 |
2/4✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
|
6 | problemSolver()->robot(robot); |
| 137 | 6 | } | |
| 138 | |||
| 139 | // -------------------------------------------------------------------- | ||
| 140 | |||
| 141 | 7 | char* Robot::getRobotName() { | |
| 142 |
2/4✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
|
7 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 143 |
1/2✓ Branch 3 taken 7 times.
✗ Branch 4 not taken.
|
14 | return c_str(robot->name()); |
| 144 | 7 | } | |
| 145 | |||
| 146 | // -------------------------------------------------------------------- | ||
| 147 | |||
| 148 | ✗ | void Robot::loadRobotModel(const char* robotName, const char* rootJointType, | |
| 149 | const char* urdfName, const char* srdfName) { | ||
| 150 | try { | ||
| 151 | ✗ | pinocchio::DevicePtr_t device(problemSolver()->createRobot(robotName)); | |
| 152 | ✗ | hpp::pinocchio::urdf::loadModel(device, 0, "", std::string(rootJointType), | |
| 153 | ✗ | std::string(urdfName), | |
| 154 | ✗ | std::string(srdfName)); | |
| 155 | // Add device to the planner | ||
| 156 | ✗ | problemSolver()->robot(device); | |
| 157 | ✗ | } catch (const std::exception& exc) { | |
| 158 | hppDout(error, exc.what()); | ||
| 159 | ✗ | throw hpp::Error(exc.what()); | |
| 160 | } | ||
| 161 | } | ||
| 162 | |||
| 163 | // -------------------------------------------------------------------- | ||
| 164 | |||
| 165 | ✗ | void Robot::loadHumanoidModel(const char* robotName, const char* rootJointType, | |
| 166 | const char* urdfName, const char* srdfName) { | ||
| 167 | try { | ||
| 168 | pinocchio::HumanoidRobotPtr_t robot( | ||
| 169 | ✗ | pinocchio::HumanoidRobot::create(robotName)); | |
| 170 | ✗ | hpp::pinocchio::urdf::loadModel(robot, 0, "", std::string(rootJointType), | |
| 171 | ✗ | std::string(urdfName), | |
| 172 | ✗ | std::string(srdfName)); | |
| 173 | ✗ | hpp::pinocchio::urdf::setupHumanoidRobot(robot); | |
| 174 | // Add robot to the planner | ||
| 175 | ✗ | problemSolver()->robot(robot); | |
| 176 | ✗ | } catch (const std::exception& exc) { | |
| 177 | hppDout(error, exc.what()); | ||
| 178 | ✗ | throw hpp::Error(exc.what()); | |
| 179 | } | ||
| 180 | } | ||
| 181 | |||
| 182 | // -------------------------------------------------------------------- | ||
| 183 | |||
| 184 | 2 | void Robot::loadRobotModelFromString(const char* robotName, | |
| 185 | const char* rootJointType, | ||
| 186 | const char* urdfString, | ||
| 187 | const char* srdfString) { | ||
| 188 | try { | ||
| 189 |
3/6✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
4 | pinocchio::DevicePtr_t device(problemSolver()->createRobot(robotName)); |
| 190 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
|
6 | hpp::pinocchio::urdf::loadModelFromString( |
| 191 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
6 | device, 0, "", std::string(rootJointType), std::string(urdfString), |
| 192 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
4 | std::string(srdfString)); |
| 193 | // Add device to the planner | ||
| 194 |
2/4✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
|
2 | problemSolver()->robot(device); |
| 195 |
0/2✗ Branch 2 not taken.
✗ Branch 3 not taken.
|
2 | } catch (const std::exception& exc) { |
| 196 | hppDout(error, exc.what()); | ||
| 197 | ✗ | throw hpp::Error(exc.what()); | |
| 198 | } | ||
| 199 | 2 | } | |
| 200 | |||
| 201 | // -------------------------------------------------------------------- | ||
| 202 | |||
| 203 | ✗ | void Robot::loadHumanoidModelFromString(const char* robotName, | |
| 204 | const char* rootJointType, | ||
| 205 | const char* urdfString, | ||
| 206 | const char* srdfString) { | ||
| 207 | try { | ||
| 208 | pinocchio::HumanoidRobotPtr_t robot( | ||
| 209 | ✗ | pinocchio::HumanoidRobot::create(robotName)); | |
| 210 | ✗ | hpp::pinocchio::urdf::loadModelFromString( | |
| 211 | ✗ | robot, 0, "", std::string(rootJointType), std::string(urdfString), | |
| 212 | ✗ | std::string(srdfString)); | |
| 213 | ✗ | hpp::pinocchio::urdf::setupHumanoidRobot(robot); | |
| 214 | // Add robot to the planner | ||
| 215 | ✗ | problemSolver()->robot(robot); | |
| 216 | ✗ | } catch (const std::exception& exc) { | |
| 217 | hppDout(error, exc.what()); | ||
| 218 | ✗ | throw hpp::Error(exc.what()); | |
| 219 | } | ||
| 220 | } | ||
| 221 | |||
| 222 | // -------------------------------------------------------------------- | ||
| 223 | |||
| 224 | ✗ | Long Robot::getConfigSize() { | |
| 225 | try { | ||
| 226 | ✗ | return (Long)getRobotOrThrow(problemSolver())->configSize(); | |
| 227 | ✗ | } catch (const std::exception& exc) { | |
| 228 | hppDout(error, exc.what()); | ||
| 229 | ✗ | throw hpp::Error(exc.what()); | |
| 230 | } | ||
| 231 | } | ||
| 232 | |||
| 233 | // -------------------------------------------------------------------- | ||
| 234 | |||
| 235 | ✗ | Long Robot::getNumberDof() { | |
| 236 | try { | ||
| 237 | ✗ | return (Long)getRobotOrThrow(problemSolver())->numberDof(); | |
| 238 | ✗ | } catch (const std::exception& exc) { | |
| 239 | hppDout(error, exc.what()); | ||
| 240 | ✗ | throw hpp::Error(exc.what()); | |
| 241 | } | ||
| 242 | } | ||
| 243 | |||
| 244 | // -------------------------------------------------------------------- | ||
| 245 | |||
| 246 | template <typename T> | ||
| 247 | 26 | void addJoint(Model& model, const JointIndex parent, | |
| 248 | const Transform3s& placement, const std::string& name) { | ||
| 249 |
3/6✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 13 times.
✗ Branch 8 not taken.
|
26 | JointIndex jid = model.addJoint(parent, T(), placement, name); |
| 250 |
1/2✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
|
26 | model.addJointFrame(jid, -1); |
| 251 | 26 | } | |
| 252 | |||
| 253 | 13 | void Robot::appendJoint(const char* parentName, const char* jointName, | |
| 254 | const char* jointType, const Transform_ pos) { | ||
| 255 | using namespace pinocchio; | ||
| 256 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
13 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 257 | 13 | Model& model = robot->model(); | |
| 258 | |||
| 259 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
13 | std::string pn(parentName); |
| 260 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
13 | std::string jn(jointName); |
| 261 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
13 | std::string jt(jointType); |
| 262 | |||
| 263 | // Find parent joint | ||
| 264 | 13 | JointIndex pid = 0; | |
| 265 |
2/2✓ Branch 1 taken 11 times.
✓ Branch 2 taken 2 times.
|
13 | if (!pn.empty()) { |
| 266 |
2/4✓ Branch 1 taken 11 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 11 times.
|
11 | if (!model.existJointName(pn)) |
| 267 | ✗ | throw Error(("Joint " + pn + " not found.").c_str()); | |
| 268 |
1/2✓ Branch 1 taken 11 times.
✗ Branch 2 not taken.
|
11 | pid = model.getJointId(pn); |
| 269 | } | ||
| 270 | |||
| 271 | // Check that joint of this name does not already exist. | ||
| 272 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 13 times.
|
13 | if (model.existJointName(jn)) |
| 273 | ✗ | throw Error(("Joint " + jn + " already exists.").c_str()); | |
| 274 | |||
| 275 | // Fill position matrix | ||
| 276 |
1/2✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
|
13 | Transform3s posMatrix = toTransform3s(pos); |
| 277 | |||
| 278 | // Determine type of joint. | ||
| 279 |
2/2✓ Branch 1 taken 2 times.
✓ Branch 2 taken 11 times.
|
13 | if (jt == "FreeFlyer") |
| 280 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
2 | addJoint<JointCollection::JointModelFreeFlyer>(model, pid, posMatrix, jn); |
| 281 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 10 times.
|
11 | else if (jt == "Planar") |
| 282 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelPlanar>(model, pid, posMatrix, jn); |
| 283 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 9 times.
|
10 | else if (jt == "RX") |
| 284 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRX>(model, pid, posMatrix, jn); |
| 285 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 8 times.
|
9 | else if (jt == "RUBX") |
| 286 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRUBX>(model, pid, posMatrix, jn); |
| 287 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 7 times.
|
8 | else if (jt == "RY") |
| 288 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRY>(model, pid, posMatrix, jn); |
| 289 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 6 times.
|
7 | else if (jt == "RUBY") |
| 290 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRUBY>(model, pid, posMatrix, jn); |
| 291 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 5 times.
|
6 | else if (jt == "RZ") |
| 292 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRZ>(model, pid, posMatrix, jn); |
| 293 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 4 times.
|
5 | else if (jt == "RUBZ") |
| 294 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelRUBZ>(model, pid, posMatrix, jn); |
| 295 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 3 times.
|
4 | else if (jt == "PX") |
| 296 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelPX>(model, pid, posMatrix, jn); |
| 297 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 2 times.
|
3 | else if (jt == "PY") |
| 298 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelPY>(model, pid, posMatrix, jn); |
| 299 |
2/2✓ Branch 1 taken 1 times.
✓ Branch 2 taken 1 times.
|
2 | else if (jt == "PZ") |
| 300 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelPZ>(model, pid, posMatrix, jn); |
| 301 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | else if (jt == "Translation") |
| 302 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | addJoint<JointCollection::JointModelTranslation>(model, pid, posMatrix, jn); |
| 303 | else { | ||
| 304 | ✗ | std::ostringstream oss; | |
| 305 | ✗ | oss << "Joint type \"" << jt << "\" does not exist."; | |
| 306 | hppDout(error, oss.str()); | ||
| 307 | ✗ | throw hpp::Error(oss.str().c_str()); | |
| 308 | } | ||
| 309 | |||
| 310 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
13 | robot->createData(); |
| 311 | 13 | } | |
| 312 | |||
| 313 | // -------------------------------------------------------------------- | ||
| 314 | |||
| 315 | 1 | Names_t* Robot::getJointNames() { | |
| 316 | try { | ||
| 317 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 318 | 1 | const Model& model = robot->model(); | |
| 319 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | return toNames_t((++model.names.begin()), model.names.end()); |
| 320 |
0/2✗ Branch 2 not taken.
✗ Branch 3 not taken.
|
1 | } catch (const std::exception& exc) { |
| 321 | ✗ | throw hpp::Error(exc.what()); | |
| 322 | } | ||
| 323 | } | ||
| 324 | |||
| 325 | // -------------------------------------------------------------------- | ||
| 326 | |||
| 327 | ✗ | Names_t* Robot::getJointTypes() { | |
| 328 | try { | ||
| 329 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 330 | ✗ | const Model& model = robot->model(); | |
| 331 | ✗ | std::vector<std::string> types(model.names.size() - 1); | |
| 332 | ✗ | for (std::size_t i = 0; i < types.size(); ++i) | |
| 333 | ✗ | types[i] = model.joints[i + 1].shortname(); | |
| 334 | ✗ | return toNames_t(types.begin(), types.end()); | |
| 335 | ✗ | } catch (const std::exception& exc) { | |
| 336 | ✗ | throw hpp::Error(exc.what()); | |
| 337 | } | ||
| 338 | } | ||
| 339 | |||
| 340 | // -------------------------------------------------------------------- | ||
| 341 | |||
| 342 | 1 | Names_t* Robot::getAllJointNames() { | |
| 343 | try { | ||
| 344 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | DevicePtr_t robot = problemSolver()->robot(); |
| 345 |
1/8✗ Branch 1 not taken.
✓ Branch 2 taken 1 times.
✗ Branch 4 not taken.
✗ Branch 5 not taken.
✗ Branch 7 not taken.
✗ Branch 8 not taken.
✗ Branch 10 not taken.
✗ Branch 11 not taken.
|
1 | if (!robot) return new Names_t(0, 0, Names_t::allocbuf(0)); |
| 346 | // Compute number of real urdf joints | ||
| 347 | 1 | const Model& model = robot->model(); | |
| 348 | 1 | std::vector<std::string> jns; | |
| 349 |
2/2✓ Branch 1 taken 25 times.
✓ Branch 2 taken 1 times.
|
26 | for (std::size_t i = 0; i < model.frames.size(); ++i) |
| 350 |
1/2✓ Branch 2 taken 25 times.
✗ Branch 3 not taken.
|
25 | jns.push_back(model.frames[i].name); |
| 351 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
1 | return toNames_t(jns.begin(), jns.end()); |
| 352 |
0/2✗ Branch 4 not taken.
✗ Branch 5 not taken.
|
1 | } catch (const std::exception& exc) { |
| 353 | ✗ | throw hpp::Error(exc.what()); | |
| 354 | } | ||
| 355 | } | ||
| 356 | |||
| 357 | // -------------------------------------------------------------------- | ||
| 358 | |||
| 359 | ✗ | Names_t* Robot::getChildJointNames(const char* jointName) { | |
| 360 | try { | ||
| 361 | ✗ | DevicePtr_t robot = problemSolver()->robot(); | |
| 362 | ✗ | if (!robot) return new Names_t(0, 0, Names_t::allocbuf(0)); | |
| 363 | // Compute number of real urdf joints | ||
| 364 | ✗ | JointPtr_t j = robot->getJointByName(std::string(jointName)); | |
| 365 | ✗ | ULong size = (ULong)j->numberChildJoints(); | |
| 366 | ✗ | char** nameList = Names_t::allocbuf(size); | |
| 367 | ✗ | Names_t* jointNames = new Names_t(size, size, nameList); | |
| 368 | ✗ | for (std::size_t i = 0; i < size; ++i) { | |
| 369 | ✗ | const JointPtr_t joint = j->childJoint(i); | |
| 370 | ✗ | nameList[i] = c_str(joint->name()); | |
| 371 | } | ||
| 372 | ✗ | return jointNames; | |
| 373 | ✗ | } catch (const std::exception& exc) { | |
| 374 | ✗ | throw hpp::Error(exc.what()); | |
| 375 | } | ||
| 376 | } | ||
| 377 | |||
| 378 | // -------------------------------------------------------------------- | ||
| 379 | |||
| 380 | ✗ | char* Robot::getParentJointName(const char* jointName) { | |
| 381 | try { | ||
| 382 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 383 | ✗ | const std::string jn(jointName); | |
| 384 | ✗ | const Frame f = robot->getFrameByName(jn); | |
| 385 | |||
| 386 | char* name; | ||
| 387 | ✗ | if (f.isRootFrame()) { | |
| 388 | ✗ | name = CORBA::string_dup(""); | |
| 389 | } else { | ||
| 390 | // TODO if f.parentFrame is not of type JOINT or FIXED_JOINT | ||
| 391 | // we should continue to loop on the parent. | ||
| 392 | ✗ | name = c_str(f.parentFrame().name()); | |
| 393 | } | ||
| 394 | ✗ | return name; | |
| 395 | ✗ | } catch (const std::exception& exc) { | |
| 396 | ✗ | throw hpp::Error(exc.what()); | |
| 397 | } | ||
| 398 | } | ||
| 399 | |||
| 400 | // -------------------------------------------------------------------- | ||
| 401 | ✗ | Transform__slice* Robot::getRootJointPosition() { | |
| 402 | try { | ||
| 403 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 404 | ✗ | Frame root = robot->rootFrame(); | |
| 405 | ✗ | return toHppTransform(root.positionInParentFrame()); | |
| 406 | ✗ | } catch (const std::exception& exc) { | |
| 407 | ✗ | throw Error(exc.what()); | |
| 408 | } | ||
| 409 | } | ||
| 410 | |||
| 411 | // -------------------------------------------------------------------- | ||
| 412 | |||
| 413 | ✗ | void Robot::setRootJointPosition(const Transform_ position) { | |
| 414 | try { | ||
| 415 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 416 | ✗ | Transform3s t3f(toTransform3s(position)); | |
| 417 | ✗ | robot->rootFrame().positionInParentFrame(t3f); | |
| 418 | ✗ | robot->computeForwardKinematics(); | |
| 419 | ✗ | } catch (const std::exception& exc) { | |
| 420 | ✗ | throw Error(exc.what()); | |
| 421 | } | ||
| 422 | } | ||
| 423 | |||
| 424 | // -------------------------------------------------------------------- | ||
| 425 | |||
| 426 | ✗ | void Robot::setJointPositionInParentFrame(const char* jointName, | |
| 427 | const Transform_ position) { | ||
| 428 | try { | ||
| 429 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 430 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 431 | ✗ | frame.positionInParentFrame(toTransform3s(position)); | |
| 432 | ✗ | robot->computeForwardKinematics(); | |
| 433 | ✗ | } catch (const std::exception& exc) { | |
| 434 | ✗ | throw Error(exc.what()); | |
| 435 | } | ||
| 436 | } | ||
| 437 | |||
| 438 | // -------------------------------------------------------------------- | ||
| 439 | |||
| 440 | ✗ | hpp::floatSeq* Robot::getJointConfig(const char* jointName) { | |
| 441 | try { | ||
| 442 | // Get robot in hppPlanner object. | ||
| 443 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 444 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 445 | ✗ | if (frame.isFixed()) return new hpp::floatSeq(); | |
| 446 | ✗ | JointPtr_t joint = frame.joint(); | |
| 447 | ✗ | if (!joint) return new hpp::floatSeq(); | |
| 448 | ✗ | vector_t config = robot->currentConfiguration(); | |
| 449 | ✗ | size_type ric = joint->rankInConfiguration(); | |
| 450 | ✗ | size_type dim = joint->configSize(); | |
| 451 | ✗ | return vectorToFloatSeq(config.segment(ric, dim)); | |
| 452 | ✗ | } catch (const std::exception& exc) { | |
| 453 | ✗ | throw hpp::Error(exc.what()); | |
| 454 | } | ||
| 455 | } | ||
| 456 | |||
| 457 | // -------------------------------------------------------------------- | ||
| 458 | |||
| 459 | 12 | char* Robot::getJointType(const char* jointName) { | |
| 460 | try { | ||
| 461 | // Get robot in hppPlanner object. | ||
| 462 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
12 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 463 |
2/4✓ Branch 3 taken 12 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 12 times.
✗ Branch 7 not taken.
|
24 | Frame frame = robot->getFrameByName(jointName); |
| 464 | 12 | std::string name; | |
| 465 |
2/6✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
12 | if (frame.isFixed()) return CORBA::string_dup("anchor"); |
| 466 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | JointPtr_t joint = frame.joint(); |
| 467 |
1/4✗ Branch 1 not taken.
✓ Branch 2 taken 12 times.
✗ Branch 4 not taken.
✗ Branch 5 not taken.
|
12 | if (!joint) return CORBA::string_dup("anchor"); |
| 468 |
3/6✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 12 times.
✗ Branch 9 not taken.
|
12 | return c_str(joint->jointModel().shortname()); |
| 469 |
0/2✗ Branch 8 not taken.
✗ Branch 9 not taken.
|
12 | } catch (const std::exception& exc) { |
| 470 | ✗ | throw hpp::Error(exc.what()); | |
| 471 | } | ||
| 472 | } | ||
| 473 | |||
| 474 | // -------------------------------------------------------------------- | ||
| 475 | |||
| 476 | ✗ | void Robot::setJointConfig(const char* jointName, const hpp::floatSeq& q) { | |
| 477 | try { | ||
| 478 | // Get robot in hppPlanner object. | ||
| 479 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 480 | ✗ | JointPtr_t joint = robot->getJointByName(jointName); | |
| 481 | ✗ | if (!joint) { | |
| 482 | ✗ | std::ostringstream oss("Robot has no joint with name "); | |
| 483 | ✗ | oss << jointName; | |
| 484 | hppDout(error, oss.str()); | ||
| 485 | ✗ | throw hpp::Error(oss.str().c_str()); | |
| 486 | } | ||
| 487 | ✗ | vector_t config = robot->currentConfiguration(); | |
| 488 | ✗ | size_type ric = joint->rankInConfiguration(); | |
| 489 | ✗ | size_type dim = joint->configSize(); | |
| 490 | ✗ | if (dim != (size_type)q.length()) { | |
| 491 | ✗ | throw Error("Wrong configuration dimension"); | |
| 492 | } | ||
| 493 | ✗ | for (size_type i = 0; i < dim; i++) config[ric + i] = q[(ULong)i]; | |
| 494 | ✗ | robot->currentConfiguration(config); | |
| 495 | ✗ | robot->computeForwardKinematics(); | |
| 496 | ✗ | } catch (const std::exception& exc) { | |
| 497 | ✗ | throw hpp::Error(exc.what()); | |
| 498 | } | ||
| 499 | } | ||
| 500 | |||
| 501 | // -------------------------------------------------------------------- | ||
| 502 | |||
| 503 | ✗ | floatSeq* Robot::jointIntegrate(const floatSeq& jointCfg, const char* jointName, | |
| 504 | const floatSeq& dq, bool saturate) { | ||
| 505 | try { | ||
| 506 | // Get robot in hppPlanner object. | ||
| 507 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 508 | ✗ | JointPtr_t joint = robot->getJointByName(jointName); | |
| 509 | ✗ | if (!joint) { | |
| 510 | ✗ | std::ostringstream oss("Robot has no joint with name "); | |
| 511 | ✗ | oss << jointName; | |
| 512 | hppDout(error, oss.str()); | ||
| 513 | ✗ | throw hpp::Error(oss.str().c_str()); | |
| 514 | } | ||
| 515 | ✗ | const size_type nq = joint->configSize(), nv = joint->numberDof(); | |
| 516 | ✗ | if (nv != (size_type)dq.length()) { | |
| 517 | ✗ | throw Error("Wrong speed dimension"); | |
| 518 | } | ||
| 519 | ✗ | LiegroupElement q(floatSeqToVector(jointCfg, nq), | |
| 520 | ✗ | joint->configurationSpace()); | |
| 521 | ✗ | q += floatSeqToVector(dq, nv); | |
| 522 | ✗ | if (saturate) { | |
| 523 | ✗ | for (size_type i = 0; i < nq; ++i) { | |
| 524 | ✗ | value_type ub = joint->upperBound(i); | |
| 525 | ✗ | value_type lb = joint->lowerBound(i); | |
| 526 | ✗ | q.vector()[i] = std::min(ub, std::max(lb, q.vector()[i])); | |
| 527 | } | ||
| 528 | } | ||
| 529 | ✗ | return vectorToFloatSeq(q.vector()); | |
| 530 | ✗ | } catch (const std::exception& exc) { | |
| 531 | ✗ | throw hpp::Error(exc.what()); | |
| 532 | } | ||
| 533 | } | ||
| 534 | |||
| 535 | // -------------------------------------------------------------------- | ||
| 536 | |||
| 537 | ✗ | hpp::floatSeqSeq* Robot::getCurrentTransformation(const char* jointName) { | |
| 538 | try { | ||
| 539 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 540 | ✗ | JointPtr_t joint = robot->getJointByName(jointName); | |
| 541 | ✗ | if (!joint) { | |
| 542 | ✗ | std::ostringstream oss("Robot has no joint with name "); | |
| 543 | ✗ | oss << jointName; | |
| 544 | hppDout(error, oss.str()); | ||
| 545 | ✗ | throw hpp::Error(oss.str().c_str()); | |
| 546 | } | ||
| 547 | |||
| 548 | // join translation & rotation into homog. transformation | ||
| 549 | ✗ | const Transform3s& T = joint->currentTransformation(); | |
| 550 | ✗ | Eigen::Matrix<hpp::pinocchio::value_type, 4, 4> trafo; | |
| 551 | ✗ | trafo.block<3, 3>(0, 0) = T.rotation(); | |
| 552 | ✗ | trafo.block<3, 1>(0, 3) = T.translation(); | |
| 553 | ✗ | trafo.block<1, 4>(3, 0) << 0, 0, 0, 1; | |
| 554 | ✗ | return matrixToFloatSeqSeq(trafo); | |
| 555 | ✗ | } catch (const std::exception& exc) { | |
| 556 | ✗ | throw Error(exc.what()); | |
| 557 | } | ||
| 558 | } | ||
| 559 | |||
| 560 | // -------------------------------------------------------------------- | ||
| 561 | |||
| 562 | ✗ | Transform__slice* Robot::getJointPosition(const char* jointName) { | |
| 563 | try { | ||
| 564 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 565 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 566 | ✗ | return toHppTransform(frame.currentTransformation()); | |
| 567 | ✗ | } catch (const std::exception& exc) { | |
| 568 | ✗ | throw Error(exc.what()); | |
| 569 | } | ||
| 570 | } | ||
| 571 | |||
| 572 | // -------------------------------------------------------------------- | ||
| 573 | |||
| 574 | ✗ | TransformSeq* Robot::getJointsPosition(const floatSeq& dofArray, | |
| 575 | const Names_t& jointNames) { | ||
| 576 | try { | ||
| 577 | using hpp::pinocchio::DeviceSync; | ||
| 578 | ✗ | DevicePtr_t _robot = getRobotOrThrow(problemSolver()); | |
| 579 | ✗ | Configuration_t config = floatSeqToConfig(_robot, dofArray, true); | |
| 580 | ✗ | DeviceSync robot(_robot); | |
| 581 | ✗ | robot.currentConfiguration(config); | |
| 582 | ✗ | robot.computeForwardKinematics(); | |
| 583 | ✗ | robot.computeFramesForwardKinematics(); | |
| 584 | |||
| 585 | ✗ | const Model& model(robot.model()); | |
| 586 | ✗ | const Data& data(robot.data()); | |
| 587 | ✗ | TransformSeq* transforms = new TransformSeq(); | |
| 588 | ✗ | transforms->length(jointNames.length()); | |
| 589 | ✗ | std::string n; | |
| 590 | ✗ | for (CORBA::ULong i = 0; i < jointNames.length(); ++i) { | |
| 591 | ✗ | n = jointNames[i]; | |
| 592 | ✗ | if (!model.existFrame(n)) { | |
| 593 | ✗ | HPP_THROW(Error, "Robot has no frame with name " << n); | |
| 594 | } | ||
| 595 | ✗ | FrameIndex joint = model.getFrameId(n); | |
| 596 | ✗ | if (model.frames.size() <= (std::size_t)joint) | |
| 597 | ✗ | HPP_THROW(Error, | |
| 598 | "Frame index of joint " << n << " out of bounds: " << joint); | ||
| 599 | |||
| 600 | ✗ | toHppTransform(data.oMf[joint], (*transforms)[i]); | |
| 601 | } | ||
| 602 | ✗ | return transforms; | |
| 603 | ✗ | } catch (const std::exception& exc) { | |
| 604 | ✗ | throw Error(exc.what()); | |
| 605 | } | ||
| 606 | } | ||
| 607 | |||
| 608 | // -------------------------------------------------------------------- | ||
| 609 | |||
| 610 | ✗ | floatSeq* Robot::getJointVelocity(const char* jointName) { | |
| 611 | try { | ||
| 612 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 613 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 614 | ✗ | vector_t w = frame.jacobian() * robot->currentVelocity(); | |
| 615 | ✗ | w.head<3>() = frame.currentTransformation().rotation() * w.head<3>(); | |
| 616 | ✗ | w.tail<3>() = frame.currentTransformation().rotation() * w.tail<3>(); | |
| 617 | ✗ | return vectorToFloatSeq(w); | |
| 618 | ✗ | } catch (const std::exception& exc) { | |
| 619 | ✗ | throw Error(exc.what()); | |
| 620 | } | ||
| 621 | } | ||
| 622 | |||
| 623 | // -------------------------------------------------------------------- | ||
| 624 | |||
| 625 | ✗ | floatSeq* Robot::getJointVelocityInLocalFrame(const char* jointName) { | |
| 626 | try { | ||
| 627 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 628 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 629 | ✗ | return vectorToFloatSeq(frame.jacobian() * robot->currentVelocity()); | |
| 630 | ✗ | } catch (const std::exception& exc) { | |
| 631 | ✗ | throw Error(exc.what()); | |
| 632 | } | ||
| 633 | } | ||
| 634 | |||
| 635 | // -------------------------------------------------------------------- | ||
| 636 | |||
| 637 | ✗ | Transform__slice* Robot::getJointPositionInParentFrame(const char* jointName) { | |
| 638 | try { | ||
| 639 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 640 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 641 | ✗ | return toHppTransform(frame.positionInParentFrame()); | |
| 642 | ✗ | } catch (const std::exception& exc) { | |
| 643 | ✗ | throw Error(exc.what()); | |
| 644 | } | ||
| 645 | } | ||
| 646 | |||
| 647 | // -------------------------------------------------------------------- | ||
| 648 | |||
| 649 | 12 | Long Robot::getJointNumberDof(const char* jointName) { | |
| 650 | try { | ||
| 651 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
12 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 652 |
2/4✓ Branch 3 taken 12 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 12 times.
✗ Branch 7 not taken.
|
24 | Frame frame = robot->getFrameByName(jointName); |
| 653 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 12 times.
|
12 | if (frame.isFixed()) return 0; |
| 654 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | JointPtr_t joint = frame.joint(); |
| 655 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
|
12 | return (joint ? (Long)joint->numberDof() : 0); |
| 656 |
0/2✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
12 | } catch (const std::exception& exc) { |
| 657 | ✗ | throw Error(exc.what()); | |
| 658 | } | ||
| 659 | } | ||
| 660 | |||
| 661 | // -------------------------------------------------------------------- | ||
| 662 | |||
| 663 | 12 | Long Robot::getJointConfigSize(const char* jointName) { | |
| 664 | try { | ||
| 665 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
12 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 666 |
2/4✓ Branch 3 taken 12 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 12 times.
✗ Branch 7 not taken.
|
24 | Frame frame = robot->getFrameByName(jointName); |
| 667 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 12 times.
|
12 | if (frame.isFixed()) return 0; |
| 668 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | JointPtr_t joint = frame.joint(); |
| 669 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
|
12 | return (joint ? (Long)joint->configSize() : 0); |
| 670 |
0/2✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
12 | } catch (const std::exception& exc) { |
| 671 | ✗ | throw Error(exc.what()); | |
| 672 | } | ||
| 673 | } | ||
| 674 | |||
| 675 | // -------------------------------------------------------------------- | ||
| 676 | |||
| 677 | ✗ | floatSeq* Robot::getJointBounds(const char* jointName) { | |
| 678 | try { | ||
| 679 | // Get robot in ProblemSolver object. | ||
| 680 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 681 | // get joint | ||
| 682 | ✗ | JointPtr_t joint = robot->getJointByName(jointName); | |
| 683 | ✗ | if (!joint) { | |
| 684 | ✗ | HPP_THROW(std::invalid_argument, "Joint " << jointName << " not found."); | |
| 685 | } | ||
| 686 | ✗ | return localGetJointBounds(joint); | |
| 687 | ✗ | } catch (const std::exception& exc) { | |
| 688 | ✗ | throw hpp::Error(exc.what()); | |
| 689 | } | ||
| 690 | } | ||
| 691 | |||
| 692 | // -------------------------------------------------------------------- | ||
| 693 | |||
| 694 | ✗ | void Robot::setJointBounds(const char* jointName, const floatSeq& jointBounds) { | |
| 695 | try { | ||
| 696 | // Get robot in ProblemSolver object. | ||
| 697 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 698 | |||
| 699 | // get joint | ||
| 700 | ✗ | JointPtr_t joint = robot->getJointByName(jointName); | |
| 701 | ✗ | localSetJointBounds(joint, floatSeqToVector(jointBounds)); | |
| 702 | ✗ | } catch (const std::exception& exc) { | |
| 703 | ✗ | throw hpp::Error(exc.what()); | |
| 704 | } | ||
| 705 | } | ||
| 706 | |||
| 707 | // -------------------------------------------------------------------- | ||
| 708 | |||
| 709 | ✗ | Transform__slice* Robot::getLinkPosition(const char* linkName) { | |
| 710 | try { | ||
| 711 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 712 | ✗ | if (!robot->model().existBodyName(std::string(linkName))) { | |
| 713 | ✗ | HPP_THROW(Error, "Robot has no link with name " << linkName); | |
| 714 | } | ||
| 715 | ✗ | FrameIndex body = robot->model().getBodyId(std::string(linkName)); | |
| 716 | ✗ | const ::pinocchio::Frame& frame = robot->model().frames[body]; | |
| 717 | ✗ | JointIndex joint = frame.parent; | |
| 718 | ✗ | if (frame.type != ::pinocchio::BODY) | |
| 719 | ✗ | HPP_THROW(Error, linkName << " is not a link"); | |
| 720 | ✗ | if (robot->model().joints.size() <= (std::size_t)joint) | |
| 721 | ✗ | HPP_THROW(Error, "Joint index of link " << linkName | |
| 722 | << " out of bounds: " << joint); | ||
| 723 | |||
| 724 | ✗ | Transform3s T = robot->data().oMi[joint] * frame.placement; | |
| 725 | ✗ | return toHppTransform(T); | |
| 726 | ✗ | } catch (const std::exception& exc) { | |
| 727 | ✗ | throw Error(exc.what()); | |
| 728 | } | ||
| 729 | } | ||
| 730 | |||
| 731 | // -------------------------------------------------------------------- | ||
| 732 | |||
| 733 | ✗ | TransformSeq* Robot::getLinksPosition(const floatSeq& dofArray, | |
| 734 | const Names_t& linkNames) { | ||
| 735 | try { | ||
| 736 | using hpp::pinocchio::DeviceSync; | ||
| 737 | ✗ | DevicePtr_t _robot = getRobotOrThrow(problemSolver()); | |
| 738 | ✗ | Configuration_t config = floatSeqToConfig(_robot, dofArray, true); | |
| 739 | ✗ | DeviceSync robot(_robot); | |
| 740 | ✗ | robot.currentConfiguration(config); | |
| 741 | ✗ | robot.computeFramesForwardKinematics(); | |
| 742 | |||
| 743 | ✗ | const Model& model(robot.model()); | |
| 744 | ✗ | const Data& data(robot.data()); | |
| 745 | ✗ | TransformSeq* transforms = new TransformSeq(); | |
| 746 | ✗ | transforms->length(linkNames.length()); | |
| 747 | ✗ | std::string n; | |
| 748 | ✗ | for (CORBA::ULong i = 0; i < linkNames.length(); ++i) { | |
| 749 | ✗ | n = linkNames[i]; | |
| 750 | ✗ | if (!model.existBodyName(n)) { | |
| 751 | ✗ | HPP_THROW(Error, "Robot has no link with name " << n); | |
| 752 | } | ||
| 753 | ✗ | FrameIndex body = model.getBodyId(n); | |
| 754 | ✗ | const ::pinocchio::Frame& frame = model.frames[body]; | |
| 755 | ✗ | if (frame.type != ::pinocchio::BODY) | |
| 756 | ✗ | HPP_THROW(Error, n << " is not a link"); | |
| 757 | |||
| 758 | ✗ | toHppTransform(data.oMf[body], (*transforms)[i]); | |
| 759 | } | ||
| 760 | ✗ | return transforms; | |
| 761 | ✗ | } catch (const std::exception& exc) { | |
| 762 | ✗ | throw Error(exc.what()); | |
| 763 | } | ||
| 764 | } | ||
| 765 | |||
| 766 | // -------------------------------------------------------------------- | ||
| 767 | |||
| 768 | ✗ | Names_t* Robot::getLinkNames(const char* jointName) { | |
| 769 | try { | ||
| 770 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 771 | ✗ | const Model& model = robot->model(); | |
| 772 | ✗ | Frame frame = robot->getFrameByName(jointName); | |
| 773 | |||
| 774 | ✗ | std::vector<std::string> names; | |
| 775 | ✗ | for (size_type i = 0; i < (size_type)model.frames.size(); ++i) { | |
| 776 | ✗ | const ::pinocchio::Frame& f = model.frames[i]; | |
| 777 | ✗ | if (f.type == ::pinocchio::BODY && f.previousFrame == frame.index()) | |
| 778 | ✗ | names.push_back(f.name); | |
| 779 | } | ||
| 780 | ✗ | return toNames_t(names.begin(), names.end()); | |
| 781 | ✗ | } catch (const std::exception& exc) { | |
| 782 | ✗ | throw Error(exc.what()); | |
| 783 | } | ||
| 784 | } | ||
| 785 | |||
| 786 | // -------------------------------------------------------------------- | ||
| 787 | |||
| 788 | ✗ | void Robot::setDimensionExtraConfigSpace(ULong dimension) { | |
| 789 | // Get robot in ProblemSolver object. | ||
| 790 | try { | ||
| 791 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 792 | ✗ | robot->setDimensionExtraConfigSpace(dimension); | |
| 793 | ✗ | } catch (const std::exception& exc) { | |
| 794 | ✗ | throw hpp::Error(exc.what()); | |
| 795 | } | ||
| 796 | } | ||
| 797 | |||
| 798 | ✗ | ULong Robot::getDimensionExtraConfigSpace() { | |
| 799 | // Get robot in ProblemSolver object. | ||
| 800 | ULong dim; | ||
| 801 | try { | ||
| 802 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 803 | ✗ | dim = (ULong)robot->extraConfigSpace().dimension(); | |
| 804 | ✗ | } catch (const std::exception& exc) { | |
| 805 | ✗ | throw hpp::Error(exc.what()); | |
| 806 | } | ||
| 807 | ✗ | return dim; | |
| 808 | } | ||
| 809 | |||
| 810 | // -------------------------------------------------------------------- | ||
| 811 | |||
| 812 | ✗ | void Robot::setExtraConfigSpaceBounds(const hpp::floatSeq& bounds) { | |
| 813 | using hpp::pinocchio::ExtraConfigSpace; | ||
| 814 | // Get robot in ProblemSolver object. | ||
| 815 | try { | ||
| 816 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 817 | ✗ | ExtraConfigSpace& extraCS = robot->extraConfigSpace(); | |
| 818 | ✗ | size_type nbBounds = (size_type)bounds.length(); | |
| 819 | ✗ | size_type dimension = extraCS.dimension(); | |
| 820 | ✗ | if (nbBounds == 2 * dimension) { | |
| 821 | ✗ | for (size_type iDof = 0; iDof < dimension; ++iDof) { | |
| 822 | ✗ | double vMin = bounds[(ULong)(2 * iDof)]; | |
| 823 | ✗ | double vMax = bounds[(ULong)(2 * iDof + 1)]; | |
| 824 | ✗ | if (vMin <= vMax) { | |
| 825 | /* Dof is actually bounded */ | ||
| 826 | ✗ | extraCS.lower(iDof) = vMin; | |
| 827 | ✗ | extraCS.upper(iDof) = vMax; | |
| 828 | } else { | ||
| 829 | /* Dof is not bounded */ | ||
| 830 | ✗ | extraCS.lower(iDof) = -std::numeric_limits<double>::infinity(); | |
| 831 | ✗ | extraCS.upper(iDof) = +std::numeric_limits<double>::infinity(); | |
| 832 | } | ||
| 833 | } | ||
| 834 | } else { | ||
| 835 | ✗ | std::ostringstream oss("Expected list of "); | |
| 836 | ✗ | oss << 2 * dimension << "float, got " << nbBounds << "."; | |
| 837 | ✗ | throw hpp::Error(oss.str().c_str()); | |
| 838 | } | ||
| 839 | ✗ | } catch (const std::exception& exc) { | |
| 840 | ✗ | throw hpp::Error(exc.what()); | |
| 841 | } | ||
| 842 | } | ||
| 843 | |||
| 844 | // -------------------------------------------------------------------- | ||
| 845 | |||
| 846 | ✗ | void Robot::setCurrentConfig(const hpp::floatSeq& dofArray) { | |
| 847 | try { | ||
| 848 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 849 | // Create a config for robot initialized with dof vector. | ||
| 850 | ✗ | Configuration_t config = floatSeqToConfig(robot, dofArray, true); | |
| 851 | ✗ | robot->currentConfiguration(config); | |
| 852 | ✗ | robot->computeForwardKinematics(); | |
| 853 | ✗ | robot->computeFramesForwardKinematics(); | |
| 854 | ✗ | } catch (const std::exception& exc) { | |
| 855 | ✗ | throw hpp::Error(exc.what()); | |
| 856 | } | ||
| 857 | } | ||
| 858 | |||
| 859 | // -------------------------------------------------------------------- | ||
| 860 | |||
| 861 | ✗ | hpp::floatSeq* Robot::shootRandomConfig() { | |
| 862 | try { | ||
| 863 | ✗ | core::ProblemPtr_t p = problemSolver()->problem(); | |
| 864 | ✗ | if (p) { | |
| 865 | ✗ | Configuration_t q; | |
| 866 | ✗ | p->configurationShooter()->shoot(q); | |
| 867 | ✗ | return vectorToFloatSeq(q); | |
| 868 | ✗ | } else { | |
| 869 | ✗ | throw Error("No problem in the ProblemSolver"); | |
| 870 | } | ||
| 871 | ✗ | } catch (const std::exception& exc) { | |
| 872 | ✗ | throw hpp::Error(exc.what()); | |
| 873 | } | ||
| 874 | } | ||
| 875 | |||
| 876 | // -------------------------------------------------------------------- | ||
| 877 | |||
| 878 | ✗ | hpp::floatSeq* Robot::getCurrentConfig() { | |
| 879 | try { | ||
| 880 | // Get robot in hppPlanner object. | ||
| 881 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 882 | ✗ | vector_t config = robot->currentConfiguration(); | |
| 883 | ✗ | assert(robot->configSize() == config.size()); | |
| 884 | ✗ | return vectorToFloatSeq(config); | |
| 885 | ✗ | } catch (const std::exception& exc) { | |
| 886 | ✗ | throw hpp::Error(exc.what()); | |
| 887 | } | ||
| 888 | } | ||
| 889 | |||
| 890 | // -------------------------------------------------------------------- | ||
| 891 | |||
| 892 | ✗ | hpp::floatSeq* Robot::getCurrentVelocity() { | |
| 893 | try { | ||
| 894 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 895 | ✗ | vector_t qDot = robot->currentVelocity(); | |
| 896 | ✗ | assert(robot->numberDof() == qDot.size()); | |
| 897 | ✗ | return vectorToFloatSeq(qDot); | |
| 898 | ✗ | } catch (const std::exception& exc) { | |
| 899 | ✗ | throw hpp::Error(exc.what()); | |
| 900 | } | ||
| 901 | } | ||
| 902 | |||
| 903 | // -------------------------------------------------------------------- | ||
| 904 | |||
| 905 | ✗ | void Robot::setCurrentVelocity(const hpp::floatSeq& qDot) { | |
| 906 | try { | ||
| 907 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 908 | ✗ | robot->currentVelocity(floatSeqToVector(qDot, robot->numberDof())); | |
| 909 | ✗ | robot->computeForwardKinematics(); | |
| 910 | ✗ | } catch (const std::exception& exc) { | |
| 911 | ✗ | throw hpp::Error(exc.what()); | |
| 912 | } | ||
| 913 | } | ||
| 914 | |||
| 915 | // -------------------------------------------------------------------- | ||
| 916 | |||
| 917 | ✗ | Names_t* Robot::getJointInnerObjects(const char* jointName) { | |
| 918 | ✗ | Names_t* innerObjectSeq = 0x0; | |
| 919 | ✗ | JointPtr_t joint; | |
| 920 | try { | ||
| 921 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 922 | ✗ | joint = robot->getJointByName(std::string(jointName)); | |
| 923 | ✗ | if (!joint) { | |
| 924 | hppDout(error, "No joint with name " << jointName); | ||
| 925 | ✗ | innerObjectSeq = new Names_t(0); | |
| 926 | ✗ | return innerObjectSeq; | |
| 927 | } | ||
| 928 | ✗ | BodyPtr_t body = joint->linkedBody(); | |
| 929 | ✗ | if (!body) { | |
| 930 | hppDout(error, "Joint " << jointName << " has no body."); | ||
| 931 | ✗ | innerObjectSeq = new Names_t(0); | |
| 932 | ✗ | return innerObjectSeq; | |
| 933 | } | ||
| 934 | |||
| 935 | ✗ | if (body->nbInnerObjects() > 0) { | |
| 936 | // Allocate result now that the size is known. | ||
| 937 | ✗ | ULong size = (ULong)body->nbInnerObjects(); | |
| 938 | ✗ | char** nameList = Names_t::allocbuf(size); | |
| 939 | ✗ | innerObjectSeq = new Names_t(size, size, nameList); | |
| 940 | ✗ | for (size_type i = 0; i < body->nbInnerObjects(); i++) { | |
| 941 | ✗ | CollisionObjectConstPtr_t object = body->innerObjectAt(i); | |
| 942 | ✗ | nameList[i] = c_str(object->name()); | |
| 943 | } | ||
| 944 | } else { | ||
| 945 | ✗ | innerObjectSeq = new Names_t(0); | |
| 946 | } | ||
| 947 | ✗ | return innerObjectSeq; | |
| 948 | ✗ | } catch (const std::exception& exc) { | |
| 949 | ✗ | throw hpp::Error(exc.what()); | |
| 950 | } | ||
| 951 | } | ||
| 952 | |||
| 953 | // -------------------------------------------------------------------- | ||
| 954 | |||
| 955 | ✗ | Names_t* Robot::getJointOuterObjects(const char* jointName) { | |
| 956 | ✗ | Names_t* outerObjectSeq = 0x0; | |
| 957 | ✗ | JointPtr_t joint; | |
| 958 | |||
| 959 | try { | ||
| 960 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 961 | ✗ | joint = robot->getJointByName(std::string(jointName)); | |
| 962 | ✗ | if (!joint) { | |
| 963 | hppDout(error, "No joint with name " << jointName); | ||
| 964 | ✗ | outerObjectSeq = new Names_t(0); | |
| 965 | ✗ | return outerObjectSeq; | |
| 966 | } | ||
| 967 | ✗ | BodyPtr_t body = joint->linkedBody(); | |
| 968 | ✗ | if (!body) { | |
| 969 | hppDout(error, "Joint " << jointName << " has no body."); | ||
| 970 | ✗ | outerObjectSeq = new Names_t(0); | |
| 971 | ✗ | return outerObjectSeq; | |
| 972 | } | ||
| 973 | |||
| 974 | ✗ | if (body->nbOuterObjects() > 0) { | |
| 975 | // Allocate result now that the size is known. | ||
| 976 | ✗ | ULong size = (ULong)body->nbOuterObjects(); | |
| 977 | ✗ | char** nameList = Names_t::allocbuf(size); | |
| 978 | ✗ | outerObjectSeq = new Names_t(size, size, nameList); | |
| 979 | ✗ | for (size_type i = 0; i < body->nbOuterObjects(); i++) { | |
| 980 | ✗ | CollisionObjectConstPtr_t object = body->outerObjectAt(i); | |
| 981 | ✗ | nameList[i] = c_str(object->name()); | |
| 982 | } | ||
| 983 | } else { | ||
| 984 | ✗ | outerObjectSeq = new Names_t(0); | |
| 985 | } | ||
| 986 | ✗ | return outerObjectSeq; | |
| 987 | ✗ | } catch (const std::exception& exc) { | |
| 988 | ✗ | throw hpp::Error(exc.what()); | |
| 989 | } | ||
| 990 | } | ||
| 991 | |||
| 992 | // -------------------------------------------------------------------- | ||
| 993 | |||
| 994 | ✗ | CollisionObjectConstPtr_t Robot::getObjectByName(const char* name) { | |
| 995 | try { | ||
| 996 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 997 | ✗ | for (size_type i = 0; i < robot->nbObjects(); ++i) { | |
| 998 | ✗ | CollisionObjectConstPtr_t object = robot->objectAt(i); | |
| 999 | ✗ | if (object->name() == name) { | |
| 1000 | ✗ | return object; | |
| 1001 | } | ||
| 1002 | } | ||
| 1003 | ✗ | throw std::runtime_error("robot has no object with name " + | |
| 1004 | ✗ | std::string(name)); | |
| 1005 | ✗ | } catch (const std::exception& exc) { | |
| 1006 | ✗ | throw hpp::Error(exc.what()); | |
| 1007 | } | ||
| 1008 | } | ||
| 1009 | |||
| 1010 | // -------------------------------------------------------------------- | ||
| 1011 | |||
| 1012 | ✗ | void Robot::getObjectPosition(const char* objectName, Transform_ cfg) { | |
| 1013 | try { | ||
| 1014 | ✗ | CollisionObjectConstPtr_t object = getObjectByName(objectName); | |
| 1015 | ✗ | Transform3s transform = object->getTransform(); | |
| 1016 | ✗ | toHppTransform(transform, cfg); | |
| 1017 | ✗ | return; | |
| 1018 | ✗ | } catch (const std::exception& exc) { | |
| 1019 | ✗ | throw hpp::Error(exc.what()); | |
| 1020 | } | ||
| 1021 | } | ||
| 1022 | |||
| 1023 | // -------------------------------------------------------------------- | ||
| 1024 | |||
| 1025 | ✗ | void Robot::isConfigValid(const hpp::floatSeq& dofArray, Boolean& validity, | |
| 1026 | CORBA::String_out report) { | ||
| 1027 | try { | ||
| 1028 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1029 | ✗ | Configuration_t config = floatSeqToConfig(robot, dofArray, true); | |
| 1030 | ✗ | core::ValidationReportPtr_t validationReport; | |
| 1031 | ✗ | validity = problemSolver()->problem()->configValidations()->validate( | |
| 1032 | config, validationReport); | ||
| 1033 | ✗ | if (validity) { | |
| 1034 | ✗ | report = CORBA::string_dup(""); | |
| 1035 | } else { | ||
| 1036 | ✗ | std::ostringstream oss; | |
| 1037 | ✗ | oss << *validationReport; | |
| 1038 | ✗ | report = CORBA::string_dup(oss.str().c_str()); | |
| 1039 | } | ||
| 1040 | ✗ | } catch (const std::exception& exc) { | |
| 1041 | ✗ | throw hpp::Error(exc.what()); | |
| 1042 | } | ||
| 1043 | } | ||
| 1044 | |||
| 1045 | // -------------------------------------------------------------------- | ||
| 1046 | |||
| 1047 | ✗ | void Robot::distancesToCollision(hpp::floatSeq_out distances, | |
| 1048 | Names_t_out innerObjects, | ||
| 1049 | Names_t_out outerObjects, | ||
| 1050 | hpp::floatSeqSeq_out innerPoints, | ||
| 1051 | hpp::floatSeqSeq_out outerPoints) { | ||
| 1052 | try { | ||
| 1053 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1054 | const DistanceBetweenObjectsPtr_t& distanceBetweenObjects = | ||
| 1055 | ✗ | problemSolver()->distanceBetweenObjects(); | |
| 1056 | ✗ | robot->computeDistances(); | |
| 1057 | ✗ | const pinocchio::GeomModel& geomModel(robot->geomModel()); | |
| 1058 | ✗ | const pinocchio::GeomData& geomData(robot->geomData()); | |
| 1059 | |||
| 1060 | ✗ | distanceBetweenObjects->computeDistances(); | |
| 1061 | ✗ | const CollisionPairs_t& cps = distanceBetweenObjects->collisionPairs(); | |
| 1062 | ✗ | const DistanceResults_t& drs = distanceBetweenObjects->distanceResults(); | |
| 1063 | |||
| 1064 | ✗ | const std::size_t nbAutoCol = geomModel.collisionPairs.size(); | |
| 1065 | ✗ | const std::size_t nbObsCol = drs.size(); | |
| 1066 | ✗ | const std::size_t nbDistPairs = nbAutoCol + nbObsCol; | |
| 1067 | |||
| 1068 | ✗ | hpp::core::vector_t dists(nbDistPairs); | |
| 1069 | ✗ | std::vector<std::string> innerObj(nbDistPairs); | |
| 1070 | ✗ | std::vector<std::string> outerObj(nbDistPairs); | |
| 1071 | ✗ | hpp::core::matrix_t innerPts(nbDistPairs, 3); | |
| 1072 | ✗ | hpp::core::matrix_t outerPts(nbDistPairs, 3); | |
| 1073 | |||
| 1074 | ✗ | for (std::size_t i = 0; i < nbAutoCol; ++i) { | |
| 1075 | ✗ | const ::pinocchio::CollisionPair& cp(geomModel.collisionPairs[i]); | |
| 1076 | ✗ | dists[i] = geomData.distanceResults[i].min_distance; | |
| 1077 | ✗ | innerObj[i] = geomModel.geometryObjects[cp.first].name; | |
| 1078 | ✗ | outerObj[i] = geomModel.geometryObjects[cp.second].name; | |
| 1079 | |||
| 1080 | ✗ | innerPts.row(i) = geomData.distanceResults[i].nearest_points[0]; | |
| 1081 | ✗ | outerPts.row(i) = geomData.distanceResults[i].nearest_points[1]; | |
| 1082 | } | ||
| 1083 | ✗ | for (std::size_t i = 0; i < nbObsCol; ++i) { | |
| 1084 | ✗ | dists[nbAutoCol + i] = drs[i].min_distance; | |
| 1085 | ✗ | innerObj[nbAutoCol + i] = cps[i].first->name(); | |
| 1086 | ✗ | outerObj[nbAutoCol + i] = cps[i].second->name(); | |
| 1087 | |||
| 1088 | ✗ | innerPts.row(nbAutoCol + i) = drs[i].nearest_points[0]; | |
| 1089 | ✗ | outerPts.row(nbAutoCol + i) = drs[i].nearest_points[1]; | |
| 1090 | } | ||
| 1091 | ✗ | distances = vectorToFloatSeq(dists); | |
| 1092 | ✗ | innerObjects = toNames_t(innerObj.begin(), innerObj.end()); | |
| 1093 | ✗ | outerObjects = toNames_t(outerObj.begin(), outerObj.end()); | |
| 1094 | ✗ | innerPoints = matrixToFloatSeqSeq(innerPts); | |
| 1095 | ✗ | outerPoints = matrixToFloatSeqSeq(outerPts); | |
| 1096 | ✗ | } catch (const std::exception& exc) { | |
| 1097 | ✗ | throw hpp::Error(exc.what()); | |
| 1098 | } | ||
| 1099 | } | ||
| 1100 | |||
| 1101 | // -------------------------------------------------------------------- | ||
| 1102 | |||
| 1103 | ✗ | void Robot::autocollisionCheck(hpp::boolSeq_out collide) { | |
| 1104 | try { | ||
| 1105 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1106 | ✗ | robot->collisionTest(false); | |
| 1107 | ✗ | const pinocchio::GeomModel& geomModel(robot->geomModel()); | |
| 1108 | ✗ | const pinocchio::GeomData& geomData(robot->geomData()); | |
| 1109 | |||
| 1110 | ✗ | const std::size_t nbColPairs = geomModel.collisionPairs.size(); | |
| 1111 | |||
| 1112 | ✗ | boolSeq* col_ptr = new boolSeq(); | |
| 1113 | ✗ | col_ptr->length((ULong)nbColPairs); | |
| 1114 | ✗ | collide = col_ptr; | |
| 1115 | |||
| 1116 | ✗ | for (std::size_t i = 0; i < nbColPairs; ++i) | |
| 1117 | ✗ | (*col_ptr)[(ULong)i] = geomData.collisionResults[i].isCollision(); | |
| 1118 | ✗ | } catch (const std::exception& exc) { | |
| 1119 | ✗ | throw hpp::Error(exc.what()); | |
| 1120 | } | ||
| 1121 | } | ||
| 1122 | |||
| 1123 | // -------------------------------------------------------------------- | ||
| 1124 | |||
| 1125 | ✗ | void Robot::autocollisionPairs(Names_t_out innerObjects, | |
| 1126 | Names_t_out outerObjects, boolSeq_out active) { | ||
| 1127 | try { | ||
| 1128 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1129 | ✗ | const pinocchio::GeomModel& geomModel(robot->geomModel()); | |
| 1130 | ✗ | const pinocchio::GeomData& geomData(robot->geomData()); | |
| 1131 | |||
| 1132 | ✗ | const std::size_t nbAutoCol = geomModel.collisionPairs.size(); | |
| 1133 | |||
| 1134 | ✗ | std::vector<std::string> innerObj(nbAutoCol); | |
| 1135 | ✗ | std::vector<std::string> outerObj(nbAutoCol); | |
| 1136 | |||
| 1137 | ✗ | boolSeq* active_ptr = new boolSeq(); | |
| 1138 | ✗ | active_ptr->length((ULong)nbAutoCol); | |
| 1139 | ✗ | active = active_ptr; | |
| 1140 | |||
| 1141 | ✗ | for (std::size_t i = 0; i < nbAutoCol; ++i) { | |
| 1142 | ✗ | const ::pinocchio::CollisionPair& cp(geomModel.collisionPairs[i]); | |
| 1143 | ✗ | innerObj[i] = geomModel.geometryObjects[cp.first].name; | |
| 1144 | ✗ | outerObj[i] = geomModel.geometryObjects[cp.second].name; | |
| 1145 | ✗ | (*active_ptr)[(ULong)i] = geomData.activeCollisionPairs[i]; | |
| 1146 | } | ||
| 1147 | ✗ | innerObjects = toNames_t(innerObj.begin(), innerObj.end()); | |
| 1148 | ✗ | outerObjects = toNames_t(outerObj.begin(), outerObj.end()); | |
| 1149 | ✗ | } catch (const std::exception& exc) { | |
| 1150 | ✗ | throw hpp::Error(exc.what()); | |
| 1151 | } | ||
| 1152 | } | ||
| 1153 | |||
| 1154 | // -------------------------------------------------------------------- | ||
| 1155 | |||
| 1156 | ✗ | void Robot::setAutoCollision(const char* innerObject, const char* outerObject, | |
| 1157 | bool active) { | ||
| 1158 | try { | ||
| 1159 | ✗ | core::ProblemSolverPtr_t ps = problemSolver(); | |
| 1160 | ✗ | DevicePtr_t robot = getRobotOrThrow(ps); | |
| 1161 | |||
| 1162 | ✗ | const pinocchio::GeomModel& geomModel(robot->geomModel()); | |
| 1163 | ✗ | pinocchio::GeomData& geomData(robot->geomData()); | |
| 1164 | |||
| 1165 | ✗ | if (!geomModel.existGeometryName(innerObject)) | |
| 1166 | ✗ | HPP_THROW(Error, "Object " << innerObject << " not found"); | |
| 1167 | ✗ | if (!geomModel.existGeometryName(outerObject)) | |
| 1168 | ✗ | HPP_THROW(Error, "Object " << outerObject << " not found"); | |
| 1169 | ✗ | pinocchio::GeomIndex idxI = geomModel.getGeometryId(innerObject); | |
| 1170 | ✗ | pinocchio::GeomIndex idxO = geomModel.getGeometryId(outerObject); | |
| 1171 | ::pinocchio::PairIndex pid = | ||
| 1172 | ✗ | geomModel.findCollisionPair(::pinocchio::CollisionPair(idxI, idxO)); | |
| 1173 | |||
| 1174 | ✗ | if (pid >= geomModel.collisionPairs.size()) { | |
| 1175 | ✗ | HPP_THROW(Error, "Collision pair (" << innerObject << ", " << outerObject | |
| 1176 | << ") not found"); | ||
| 1177 | } | ||
| 1178 | |||
| 1179 | ✗ | if (active) | |
| 1180 | ✗ | geomData.activateCollisionPair(pid); | |
| 1181 | else | ||
| 1182 | ✗ | geomData.deactivateCollisionPair(pid); | |
| 1183 | |||
| 1184 | ✗ | ps->initValidations(); | |
| 1185 | ✗ | } catch (const std::exception& exc) { | |
| 1186 | ✗ | throw hpp::Error(exc.what()); | |
| 1187 | } | ||
| 1188 | } | ||
| 1189 | |||
| 1190 | // -------------------------------------------------------------------- | ||
| 1191 | |||
| 1192 | ✗ | Double Robot::getMass() { | |
| 1193 | try { | ||
| 1194 | ✗ | return getRobotOrThrow(problemSolver())->mass(); | |
| 1195 | ✗ | } catch (const std::exception& exc) { | |
| 1196 | ✗ | throw hpp::Error(exc.what()); | |
| 1197 | } | ||
| 1198 | } | ||
| 1199 | |||
| 1200 | // -------------------------------------------------------------------- | ||
| 1201 | |||
| 1202 | ✗ | hpp::floatSeq* Robot::getCenterOfMass() { | |
| 1203 | try { | ||
| 1204 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1205 | ✗ | robot->computeForwardKinematics(); | |
| 1206 | ✗ | return vectorToFloatSeq(robot->positionCenterOfMass()); | |
| 1207 | ✗ | } catch (const std::exception& exc) { | |
| 1208 | ✗ | throw hpp::Error(exc.what()); | |
| 1209 | } | ||
| 1210 | } | ||
| 1211 | |||
| 1212 | // -------------------------------------------------------------------- | ||
| 1213 | |||
| 1214 | ✗ | hpp::floatSeq* Robot::getCenterOfMassVelocity() { | |
| 1215 | try { | ||
| 1216 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1217 | ✗ | robot->computeForwardKinematics(pinocchio::COMPUTE_ALL); | |
| 1218 | ✗ | return vectorToFloatSeq(robot->jacobianCenterOfMass() * | |
| 1219 | ✗ | robot->currentVelocity()); | |
| 1220 | ✗ | } catch (const std::exception& exc) { | |
| 1221 | ✗ | throw hpp::Error(exc.what()); | |
| 1222 | } | ||
| 1223 | } | ||
| 1224 | |||
| 1225 | // -------------------------------------------------------------------- | ||
| 1226 | |||
| 1227 | ✗ | hpp::floatSeqSeq* Robot::getJacobianCenterOfMass() { | |
| 1228 | try { | ||
| 1229 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1230 | ✗ | robot->computeForwardKinematics(pinocchio::COMPUTE_ALL); | |
| 1231 | ✗ | const ComJacobian_t& jacobian = robot->jacobianCenterOfMass(); | |
| 1232 | ✗ | return matrixToFloatSeqSeq(jacobian); | |
| 1233 | ✗ | } catch (const std::exception& exc) { | |
| 1234 | ✗ | throw hpp::Error(exc.what()); | |
| 1235 | } | ||
| 1236 | } | ||
| 1237 | |||
| 1238 | // -------------------------------------------------------------------- | ||
| 1239 | |||
| 1240 | ✗ | void Robot::createPolyhedron(const char* polyhedronName) { | |
| 1241 | ✗ | objectMap_.createPolyhedron(polyhedronName); | |
| 1242 | } | ||
| 1243 | |||
| 1244 | // -------------------------------------------------------------------- | ||
| 1245 | |||
| 1246 | ✗ | void Robot::createBox(const char* name, Double x, Double y, Double z) { | |
| 1247 | ✗ | objectMap_.createBox(name, x, y, z); | |
| 1248 | } | ||
| 1249 | |||
| 1250 | // -------------------------------------------------------------------- | ||
| 1251 | |||
| 1252 | 12 | void Robot::createSphere(const char* name, Double radius) { | |
| 1253 |
2/4✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
|
12 | objectMap_.createSphere(name, radius); |
| 1254 | 12 | } | |
| 1255 | |||
| 1256 | // -------------------------------------------------------------------- | ||
| 1257 | |||
| 1258 | ✗ | void Robot::createCylinder(const char* name, Double radius, Double length) { | |
| 1259 | ✗ | objectMap_.createCylinder(name, radius, length); | |
| 1260 | } | ||
| 1261 | |||
| 1262 | // -------------------------------------------------------------------- | ||
| 1263 | |||
| 1264 | ✗ | ULong Robot::addPoint(const char* polyhedronName, Double x, Double y, | |
| 1265 | Double z) { | ||
| 1266 | ✗ | return static_cast<Long>(objectMap_.addPoint(polyhedronName, x, y, z)); | |
| 1267 | } | ||
| 1268 | |||
| 1269 | // -------------------------------------------------------------------- | ||
| 1270 | |||
| 1271 | ✗ | ULong Robot::addTriangle(const char* polyhedronName, ULong pt1, ULong pt2, | |
| 1272 | ULong pt3) { | ||
| 1273 | return static_cast<ULong>( | ||
| 1274 | ✗ | objectMap_.addTriangle(polyhedronName, pt1, pt2, pt3)); | |
| 1275 | } | ||
| 1276 | |||
| 1277 | // -------------------------------------------------------------------- | ||
| 1278 | |||
| 1279 | 12 | void Robot::addObjectToJoint(const char* jointName, const char* objectName, | |
| 1280 | const Transform_ pos) { | ||
| 1281 | using namespace pinocchio; | ||
| 1282 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
12 | DevicePtr_t robot = getRobotOrThrow(problemSolver()); |
| 1283 | 12 | Model& model = robot->model(); | |
| 1284 | 12 | GeomModel& geomModel = robot->geomModel(); | |
| 1285 | |||
| 1286 |
1/2✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
|
12 | std::string jn(jointName); |
| 1287 |
1/2✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
|
12 | std::string on(objectName); |
| 1288 | |||
| 1289 | // Find parent joint | ||
| 1290 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✗ Branch 3 not taken.
✓ Branch 4 taken 12 times.
|
12 | if (!model.existJointName(jn)) |
| 1291 | ✗ | throw Error(("Joint " + jn + " not found.").c_str()); | |
| 1292 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | JointIndex jid = model.getJointId(jn); |
| 1293 | |||
| 1294 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | Transform3s placement = toTransform3s(pos); |
| 1295 | |||
| 1296 | try { | ||
| 1297 |
2/4✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
|
24 | CollisionGeometryPtr_t geometry = objectMap_.geometry(objectName); |
| 1298 | |||
| 1299 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | FrameIndex bid = model.addBodyFrame(on, jid, placement); |
| 1300 |
7/14✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 12 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 12 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 12 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 12 times.
✗ Branch 22 not taken.
|
24 | GeometryObject geom(on, bid, jid, geometry, placement); |
| 1301 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
12 | GeomIndex idx = geomModel.addGeometryObject(geom, model); |
| 1302 |
2/2✓ Branch 0 taken 66 times.
✓ Branch 1 taken 12 times.
|
78 | for (GeomIndex i = 0; i < idx; ++i) { |
| 1303 |
1/2✓ Branch 1 taken 66 times.
✗ Branch 2 not taken.
|
66 | if (geomModel.geometryObjects[i].parentJoint != jid) |
| 1304 |
2/4✓ Branch 1 taken 66 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 66 times.
✗ Branch 5 not taken.
|
66 | geomModel.addCollisionPair(::pinocchio::CollisionPair(i, idx)); |
| 1305 | } | ||
| 1306 | |||
| 1307 |
1/2✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
|
12 | robot->createData(); |
| 1308 |
1/2✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
|
12 | robot->createGeomData(); |
| 1309 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
12 | problemSolver()->resetProblem(); |
| 1310 |
0/2✗ Branch 4 not taken.
✗ Branch 5 not taken.
|
12 | } catch (const std::exception& exc) { |
| 1311 | ✗ | throw hpp::Error(exc.what()); | |
| 1312 | } | ||
| 1313 | 12 | } | |
| 1314 | |||
| 1315 | ✗ | void Robot::addPartialCom(const char* comName, const Names_t& jointNames) { | |
| 1316 | try { | ||
| 1317 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1318 | pinocchio::CenterOfMassComputationPtr_t comc = | ||
| 1319 | ✗ | pinocchio::CenterOfMassComputation::create(robot); | |
| 1320 | |||
| 1321 | ✗ | for (ULong i = 0; i < jointNames.length(); ++i) { | |
| 1322 | ✗ | std::string name(jointNames[i]); | |
| 1323 | ✗ | JointPtr_t j = robot->getJointByName(name); | |
| 1324 | ✗ | if (!j) throw hpp::Error("One joint not found."); | |
| 1325 | ✗ | comc->add(j); | |
| 1326 | } | ||
| 1327 | ✗ | problemSolver()->centerOfMassComputations.add(std::string(comName), comc); | |
| 1328 | ✗ | } catch (const std::exception& exc) { | |
| 1329 | ✗ | throw hpp::Error(exc.what()); | |
| 1330 | } | ||
| 1331 | } | ||
| 1332 | |||
| 1333 | ✗ | hpp::floatSeq* Robot::getPartialCom(const char* comName) { | |
| 1334 | try { | ||
| 1335 | ✗ | if (!problemSolver()->centerOfMassComputations.has(comName)) { | |
| 1336 | ✗ | HPP_THROW(std::invalid_argument, | |
| 1337 | "Partial COM " << comName << " not found."); | ||
| 1338 | } | ||
| 1339 | pinocchio::CenterOfMassComputationPtr_t comc = | ||
| 1340 | ✗ | problemSolver()->centerOfMassComputations.get(comName); | |
| 1341 | ✗ | comc->compute(hpp::pinocchio::COM); | |
| 1342 | ✗ | return vectorToFloatSeq(comc->com()); | |
| 1343 | ✗ | } catch (const std::exception& exc) { | |
| 1344 | ✗ | throw hpp::Error(exc.what()); | |
| 1345 | } | ||
| 1346 | } | ||
| 1347 | |||
| 1348 | ✗ | hpp::floatSeq* Robot::getVelocityPartialCom(const char* comName) { | |
| 1349 | try { | ||
| 1350 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1351 | ✗ | if (!problemSolver()->centerOfMassComputations.has(comName)) { | |
| 1352 | ✗ | HPP_THROW(std::invalid_argument, | |
| 1353 | "Partial COM " << comName << " not found."); | ||
| 1354 | } | ||
| 1355 | pinocchio::CenterOfMassComputationPtr_t comc = | ||
| 1356 | ✗ | problemSolver()->centerOfMassComputations.get(comName); | |
| 1357 | ✗ | comc->compute(hpp::pinocchio::JACOBIAN); | |
| 1358 | ✗ | return vectorToFloatSeq(comc->jacobian() * robot->currentVelocity()); | |
| 1359 | ✗ | } catch (const std::exception& exc) { | |
| 1360 | ✗ | throw hpp::Error(exc.what()); | |
| 1361 | } | ||
| 1362 | } | ||
| 1363 | |||
| 1364 | ✗ | hpp::floatSeqSeq* Robot::getJacobianPartialCom(const char* comName) { | |
| 1365 | try { | ||
| 1366 | ✗ | if (!problemSolver()->centerOfMassComputations.has(comName)) { | |
| 1367 | ✗ | HPP_THROW(std::invalid_argument, | |
| 1368 | "Partial COM " << comName << " not found."); | ||
| 1369 | } | ||
| 1370 | pinocchio::CenterOfMassComputationPtr_t comc = | ||
| 1371 | ✗ | problemSolver()->centerOfMassComputations.get(comName); | |
| 1372 | ✗ | comc->compute(hpp::pinocchio::JACOBIAN); | |
| 1373 | ✗ | return matrixToFloatSeqSeq(comc->jacobian()); | |
| 1374 | ✗ | } catch (const std::exception& exc) { | |
| 1375 | ✗ | throw hpp::Error(exc.what()); | |
| 1376 | } | ||
| 1377 | } | ||
| 1378 | |||
| 1379 | hpp::pinocchio_idl::CenterOfMassComputation_ptr | ||
| 1380 | ✗ | Robot::getCenterOfMassComputation(const char* name) { | |
| 1381 | ✗ | const std::string cn(name); | |
| 1382 | ✗ | core::ProblemSolverPtr_t ps = problemSolver(); | |
| 1383 | ✗ | if (!ps->centerOfMassComputations.has(cn)) | |
| 1384 | ✗ | throw Error(("CenterOfMassComputation " + cn + " not found").c_str()); | |
| 1385 | |||
| 1386 | hpp::pinocchio_idl::CenterOfMassComputation_var d = | ||
| 1387 | makeServantDownCast<pinocchio_impl::CenterOfMassComputation>( | ||
| 1388 | ✗ | server_->parent(), ps->centerOfMassComputations.get(cn)); | |
| 1389 | ✗ | return d._retn(); | |
| 1390 | } | ||
| 1391 | |||
| 1392 | ✗ | floatSeq* Robot::getRobotAABB() { | |
| 1393 | ✗ | DevicePtr_t robot = getRobotOrThrow(problemSolver()); | |
| 1394 | try { | ||
| 1395 | ✗ | coal::AABB aabb = robot->computeAABB(); | |
| 1396 | ✗ | vector_t v(6); | |
| 1397 | ✗ | v.head<3>() = aabb.min_; | |
| 1398 | ✗ | v.tail<3>() = aabb.max_; | |
| 1399 | ✗ | return vectorToFloatSeq(v); | |
| 1400 | ✗ | } catch (const std::exception& exc) { | |
| 1401 | ✗ | throw hpp::Error(exc.what()); | |
| 1402 | } | ||
| 1403 | } | ||
| 1404 | } // end of namespace impl. | ||
| 1405 | } // end of namespace corbaServer. | ||
| 1406 | } // end of namespace hpp. | ||
| 1407 |