| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "user/user_objects.h" |
| |
|
| | #include <algorithm> |
| | #include <array> |
| | #include <cmath> |
| | #include <cstddef> |
| | #include <cstdint> |
| | #include <cstdio> |
| | #include <cstring> |
| | #include <functional> |
| | #include <limits> |
| | #include <map> |
| | #include <memory> |
| | #include <new> |
| | #include <optional> |
| | #include <random> |
| | #include <sstream> |
| | #include <string> |
| | #include <string_view> |
| | #include <utility> |
| | #include <vector> |
| |
|
| | #include "lodepng.h" |
| | #include "cc/array_safety.h" |
| | #include "engine/engine_passive.h" |
| | #include <mujoco/mjspec.h> |
| | #include <mujoco/mujoco.h> |
| | #include "user/user_api.h" |
| | #include "user/user_cache.h" |
| | #include "user/user_model.h" |
| | #include "user/user_resource.h" |
| | #include "user/user_util.h" |
| |
|
| | namespace { |
| | namespace mju = ::mujoco::util; |
| | using mujoco::user::FilePath; |
| |
|
| | class PNGImage { |
| | public: |
| | static PNGImage Load(const mjCBase* obj, mjResource* resource, |
| | LodePNGColorType color_type); |
| | int Width() const { return width_; } |
| | int Height() const { return height_; } |
| | bool IsSRGB() const { return is_srgb_; } |
| |
|
| | uint8_t operator[] (int i) const { return data_[i]; } |
| | std::vector<unsigned char>& MoveData() { return data_; } |
| |
|
| | private: |
| | std::size_t Size() const { |
| | return data_.size() + (3 * sizeof(int)); |
| | } |
| |
|
| | int width_; |
| | int height_; |
| | bool is_srgb_; |
| | LodePNGColorType color_type_; |
| | std::vector<uint8_t> data_; |
| | }; |
| |
|
| | PNGImage PNGImage::Load(const mjCBase* obj, mjResource* resource, |
| | LodePNGColorType color_type) { |
| | PNGImage image; |
| | image.color_type_ = color_type; |
| | mjCCache *cache = reinterpret_cast<mjCCache*>(mj_globalCache()); |
| |
|
| | |
| | auto callback = [&image](const void* data) { |
| | const PNGImage *cached_image = static_cast<const PNGImage*>(data); |
| | if (cached_image->color_type_ == image.color_type_) { |
| | image = *cached_image; |
| | return true; |
| | } |
| | return false; |
| | }; |
| |
|
| | |
| | if (cache && cache->PopulateData(resource, callback)) { |
| | return image; |
| | } |
| |
|
| | |
| | const unsigned char* buffer; |
| | int nbuffer = mju_readResource(resource, (const void**) &buffer); |
| |
|
| | if (nbuffer < 0) { |
| | throw mjCError(obj, "could not read PNG file '%s'", resource->name); |
| | } |
| |
|
| | if (!nbuffer) { |
| | throw mjCError(obj, "empty PNG file '%s'", resource->name); |
| | } |
| |
|
| | |
| | unsigned int w, h; |
| |
|
| | lodepng::State state; |
| | state.info_raw.colortype = image.color_type_; |
| | state.info_raw.bitdepth = 8; |
| | unsigned err = lodepng::decode(image.data_, w, h, state, buffer, nbuffer); |
| |
|
| | |
| | if (err) { |
| | std::stringstream ss; |
| | ss << "error decoding PNG file '" << resource->name << "': " << lodepng_error_text(err); |
| | throw mjCError(obj, "%s", ss.str().c_str()); |
| | } |
| |
|
| | image.width_ = w; |
| | image.height_ = h; |
| | image.is_srgb_ = (state.info_png.srgb_defined == 1); |
| |
|
| | if (image.width_ <= 0 || image.height_ < 0) { |
| | std::stringstream ss; |
| | ss << "error decoding PNG file '" << resource->name << "': " << "dimensions are invalid"; |
| | throw mjCError(obj, "%s", ss.str().c_str()); |
| | } |
| |
|
| | |
| | if (cache) { |
| | PNGImage *cached_image = new PNGImage(image);; |
| | std::size_t size = image.Size(); |
| | std::shared_ptr<const void> cached_data(cached_image, +[] (const void* data) { |
| | delete static_cast<const PNGImage*>(data); |
| | }); |
| | cache->Insert("", resource, cached_data, size); |
| | } |
| |
|
| | return image; |
| | } |
| |
|
| | |
| | template <typename T> |
| | void MapFrame(std::vector<T*>& parent, std::vector<T*>& child, |
| | mjCFrame* frame, mjCBody* parent_body) { |
| | std::for_each(child.begin(), child.end(), [frame, parent_body](T* element) { |
| | element->SetFrame(frame); |
| | element->SetParent(parent_body); |
| | }); |
| | parent.insert(parent.end(), child.begin(), child.end()); |
| | child.clear(); |
| | } |
| |
|
| | } |
| |
|
| |
|
| | |
| | static void checksize(double* size, mjtGeom type, mjCBase* object, const char* name, int id) { |
| | |
| | if (type == mjGEOM_PLANE) { |
| | if (size[2] <= 0) { |
| | throw mjCError(object, "plane size(3) must be positive"); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int i=0; i < mjGEOMINFO[type]; i++) { |
| | if (size[i] <= 0) { |
| | throw mjCError(object, "size %d must be positive in geom", nullptr, i); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | static void checklimited( |
| | const mjCBase* obj, |
| | bool autolimits, const char* entity, const char* attr, int limited, bool hasrange) { |
| | if (!autolimits && limited == 2 && hasrange) { |
| | std::stringstream ss; |
| | ss << entity << " has `" << attr << "range` but not `" << attr << "limited`. " |
| | << "set the autolimits=\"true\" compiler option, specify `" << attr << "limited` " |
| | << "explicitly (\"true\" or \"false\"), or remove the `" << attr << "range` attribute."; |
| | throw mjCError(obj, "%s", ss.str().c_str()); |
| | } |
| | } |
| |
|
| | |
| | static bool islimited(int limited, const double range[2]) { |
| | if (limited == mjLIMITED_TRUE || (limited == mjLIMITED_AUTO && range[0] < range[1])) { |
| | return true; |
| | } |
| | return false; |
| | } |
| |
|
| | |
| |
|
| | |
| | mjCError::mjCError(const mjCBase* obj, const char* msg, const char* str, int pos1, int pos2) { |
| | char temp[600]; |
| |
|
| | |
| | warning = false; |
| | if (obj || msg) { |
| | mju::sprintf_arr(message, "Error"); |
| | } else { |
| | message[0] = 0; |
| | } |
| |
|
| | |
| | if (msg) { |
| | if (str) { |
| | mju::sprintf_arr(temp, msg, str, pos1, pos2); |
| | } else { |
| | mju::sprintf_arr(temp, msg, pos1, pos2); |
| | } |
| |
|
| | mju::strcat_arr(message, ": "); |
| | mju::strcat_arr(message, temp); |
| | } |
| |
|
| | |
| | if (obj) { |
| | |
| | if (!obj->info.empty()) { |
| | mju::sprintf_arr(temp, "Element name '%s', id %d, %s", |
| | obj->name.c_str(), obj->id, obj->info.c_str()); |
| | } else { |
| | mju::sprintf_arr(temp, "Element name '%s', id %d", obj->name.c_str(), obj->id); |
| | } |
| |
|
| | |
| | mju::strcat_arr(message, "\n"); |
| | mju::strcat_arr(message, temp); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | const char* ResolveOrientation(double* quat, bool degree, const char* sequence, |
| | const mjsOrientation& orient) { |
| | double axisangle[4]; |
| | double xyaxes[6]; |
| | double zaxis[3]; |
| | double euler[3]; |
| |
|
| | mjuu_copyvec(axisangle, orient.axisangle, 4); |
| | mjuu_copyvec(xyaxes, orient.xyaxes, 6); |
| | mjuu_copyvec(zaxis, orient.zaxis, 3); |
| | mjuu_copyvec(euler, orient.euler, 3); |
| |
|
| | |
| | if (orient.type == mjORIENTATION_AXISANGLE) { |
| | |
| | if (degree) { |
| | axisangle[3] = axisangle[3] / 180.0 * mjPI; |
| | } |
| | if (mjuu_normvec(axisangle, 3) < mjEPS) { |
| | return "axisangle too small"; |
| | } |
| |
|
| | |
| | double ang2 = axisangle[3]/2; |
| | quat[0] = cos(ang2); |
| | quat[1] = sin(ang2)*axisangle[0]; |
| | quat[2] = sin(ang2)*axisangle[1]; |
| | quat[3] = sin(ang2)*axisangle[2]; |
| | } |
| |
|
| | |
| | if (orient.type == mjORIENTATION_XYAXES) { |
| | |
| | if (mjuu_normvec(xyaxes, 3) < mjEPS) { |
| | return "xaxis too small"; |
| | } |
| |
|
| | |
| | double d = mjuu_dot3(xyaxes, xyaxes+3); |
| | xyaxes[3] -= xyaxes[0]*d; |
| | xyaxes[4] -= xyaxes[1]*d; |
| | xyaxes[5] -= xyaxes[2]*d; |
| | if (mjuu_normvec(xyaxes+3, 3) < mjEPS) { |
| | return "yaxis too small"; |
| | } |
| |
|
| | |
| | double z[3]; |
| | mjuu_crossvec(z, xyaxes, xyaxes+3); |
| | if (mjuu_normvec(z, 3) < mjEPS) { |
| | return "cross(xaxis, yaxis) too small"; |
| | } |
| |
|
| | |
| | mjuu_frame2quat(quat, xyaxes, xyaxes+3, z); |
| | } |
| |
|
| | |
| | if (orient.type == mjORIENTATION_ZAXIS) { |
| | if (mjuu_normvec(zaxis, 3) < mjEPS) { |
| | return "zaxis too small"; |
| | } |
| | mjuu_z2quat(quat, zaxis); |
| | } |
| |
|
| |
|
| | |
| | if (orient.type == mjORIENTATION_EULER) { |
| | |
| | if (degree) { |
| | for (int i=0; i < 3; i++) { |
| | euler[i] = euler[i] / 180.0 * mjPI; |
| | } |
| | } |
| |
|
| | |
| | mjuu_setvec(quat, 1, 0, 0, 0); |
| |
|
| | |
| | for (int i=0; i < 3; i++) { |
| | double tmp[4], qrot[4] = {cos(euler[i]/2), 0, 0, 0}; |
| | double sa = sin(euler[i]/2); |
| |
|
| | |
| | if (sequence[i] == 'x' || sequence[i] == 'X') { |
| | qrot[1] = sa; |
| | } else if (sequence[i] == 'y' || sequence[i] == 'Y') { |
| | qrot[2] = sa; |
| | } else if (sequence[i] == 'z' || sequence[i] == 'Z') { |
| | qrot[3] = sa; |
| | } else { |
| | return "euler sequence can only contain x, y, z, X, Y, Z"; |
| | } |
| |
|
| | |
| | if (sequence[i] == 'x' || sequence[i] == 'y' || sequence[i] == 'z') { |
| | mjuu_mulquat(tmp, quat, qrot); |
| | } else { |
| | mjuu_mulquat(tmp, qrot, quat); |
| | } |
| | mjuu_copyvec(quat, tmp, 4); |
| | } |
| |
|
| | |
| | mjuu_normvec(quat, 4); |
| | } |
| |
|
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| |
|
| | |
| | void mjCBoundingVolumeHierarchy::Set(double ipos_element[3], double iquat_element[4]) { |
| | mjuu_copyvec(ipos_, ipos_element, 3); |
| | mjuu_copyvec(iquat_, iquat_element, 4); |
| | } |
| |
|
| |
|
| |
|
| | void mjCBoundingVolumeHierarchy::AllocateBoundingVolumes(int nleaf) { |
| | nbvh_ = 0; |
| | bvh_.clear(); |
| | child_.clear(); |
| | nodeid_.clear(); |
| | level_.clear(); |
| | bvleaf_.clear(); |
| | bvleaf_.reserve(nleaf); |
| | } |
| |
|
| |
|
| | void mjCBoundingVolumeHierarchy::RemoveInactiveVolumes(int nmax) { |
| | bvleaf_.erase(bvleaf_.begin() + nmax, bvleaf_.end()); |
| | } |
| |
|
| | const mjCBoundingVolume* |
| | mjCBoundingVolumeHierarchy::AddBoundingVolume(int id, int contype, int conaffinity, |
| | const double* pos, const double* quat, |
| | const double* aabb) { |
| | bvleaf_.emplace_back(id, contype, conaffinity, pos, quat, aabb); |
| | return &bvleaf_.back(); |
| | } |
| |
|
| |
|
| | const mjCBoundingVolume* |
| | mjCBoundingVolumeHierarchy::AddBoundingVolume(const int* id, int contype, int conaffinity, |
| | const double* pos, const double* quat, |
| | const double* aabb) { |
| | bvleaf_.emplace_back(id, contype, conaffinity, pos, quat, aabb); |
| | return &bvleaf_.back(); |
| | } |
| |
|
| |
|
| | |
| | void mjCBoundingVolumeHierarchy::CreateBVH() { |
| | std::vector<BVElement> elements; |
| | Make(elements); |
| | MakeBVH(elements.begin(), elements.end()); |
| | } |
| |
|
| |
|
| | void mjCBoundingVolumeHierarchy::Make(std::vector<BVElement>& elements) { |
| | |
| | |
| | elements.reserve(bvleaf_.size()); |
| | double qinv[4] = {iquat_[0], -iquat_[1], -iquat_[2], -iquat_[3]}; |
| | for (int i = 0; i < bvleaf_.size(); i++) { |
| | if (bvleaf_[i].Conaffinity() || bvleaf_[i].Contype()) { |
| | BVElement element; |
| | element.e = &bvleaf_[i]; |
| | double vert[3] = {element.e->Pos(0) - ipos_[0], |
| | element.e->Pos(1) - ipos_[1], |
| | element.e->Pos(2) - ipos_[2]}; |
| | mjuu_rotVecQuat(element.lpos, vert, qinv); |
| | elements.push_back(std::move(element)); |
| | } |
| | } |
| | } |
| |
|
| |
|
| | |
| | int mjCBoundingVolumeHierarchy::MakeBVH( |
| | std::vector<BVElement>::iterator elements_begin, |
| | std::vector<BVElement>::iterator elements_end, int lev) { |
| | int nelements = elements_end - elements_begin; |
| | if (nelements == 0) { |
| | return -1; |
| | } |
| | constexpr double kMaxVal = std::numeric_limits<double>::max(); |
| | double AAMM[6] = {kMaxVal, kMaxVal, kMaxVal, -kMaxVal, -kMaxVal, -kMaxVal}; |
| |
|
| | |
| | double qinv[4] = {iquat_[0], -iquat_[1], -iquat_[2], -iquat_[3]}; |
| |
|
| | |
| | for (auto element = elements_begin; element != elements_end; ++element) { |
| | |
| | double aamm[6] = {element->e->AABB(0) - element->e->AABB(3), |
| | element->e->AABB(1) - element->e->AABB(4), |
| | element->e->AABB(2) - element->e->AABB(5), |
| | element->e->AABB(0) + element->e->AABB(3), |
| | element->e->AABB(1) + element->e->AABB(4), |
| | element->e->AABB(2) + element->e->AABB(5)}; |
| |
|
| | |
| | for (int v=0; v < 8; v++) { |
| | double vert[3], box[3]; |
| | vert[0] = (v&1 ? aamm[3] : aamm[0]); |
| | vert[1] = (v&2 ? aamm[4] : aamm[1]); |
| | vert[2] = (v&4 ? aamm[5] : aamm[2]); |
| |
|
| | |
| | if (element->e->Quat()) { |
| | mjuu_rotVecQuat(box, vert, element->e->Quat()); |
| | box[0] += element->e->Pos(0) - ipos_[0]; |
| | box[1] += element->e->Pos(1) - ipos_[1]; |
| | box[2] += element->e->Pos(2) - ipos_[2]; |
| | mjuu_rotVecQuat(vert, box, qinv); |
| | } |
| |
|
| | AAMM[0] = std::min(AAMM[0], vert[0]); |
| | AAMM[1] = std::min(AAMM[1], vert[1]); |
| | AAMM[2] = std::min(AAMM[2], vert[2]); |
| | AAMM[3] = std::max(AAMM[3], vert[0]); |
| | AAMM[4] = std::max(AAMM[4], vert[1]); |
| | AAMM[5] = std::max(AAMM[5], vert[2]); |
| | } |
| | } |
| |
|
| | |
| | for (int i = 0; i < 3; i++) { |
| | if (std::abs(AAMM[i] - AAMM[i+3]) < mjEPS) { |
| | AAMM[i + 0] -= mjEPS; |
| | AAMM[i + 3] += mjEPS; |
| | } |
| | } |
| |
|
| | |
| | int index = nbvh_++; |
| | child_.push_back(-1); |
| | child_.push_back(-1); |
| | nodeid_.push_back(-1); |
| | nodeidptr_.push_back(nullptr); |
| | level_.push_back(lev); |
| |
|
| | |
| | bvh_.push_back((AAMM[3] + AAMM[0]) / 2); |
| | bvh_.push_back((AAMM[4] + AAMM[1]) / 2); |
| | bvh_.push_back((AAMM[5] + AAMM[2]) / 2); |
| | bvh_.push_back((AAMM[3] - AAMM[0]) / 2); |
| | bvh_.push_back((AAMM[4] - AAMM[1]) / 2); |
| | bvh_.push_back((AAMM[5] - AAMM[2]) / 2); |
| |
|
| | |
| | if (nelements == 1) { |
| | child_[2*index + 0] = -1; |
| | child_[2*index + 1] = -1; |
| | nodeid_[index] = *elements_begin->e->Id(); |
| | nodeidptr_[index] = (int*)elements_begin->e->Id(); |
| | return index; |
| | } |
| |
|
| | |
| | int axis = 0; |
| | double edges[3] = {AAMM[3] - AAMM[0], AAMM[4] - AAMM[1], AAMM[5] - AAMM[2]}; |
| | if (edges[1] >= edges[0] + mjEPS) axis = 1; |
| | if (edges[2] >= edges[axis] + mjEPS) axis = 2; |
| |
|
| | |
| | auto compare = [&](const BVElement& e1, const BVElement& e2) { |
| | if (std::abs(e1.lpos[axis] - e2.lpos[axis]) > mjEPS) { |
| | return e1.lpos[axis] < e2.lpos[axis]; |
| | } |
| | |
| | return e1.e < e2.e; |
| | }; |
| |
|
| | |
| | int m = nelements / 2; |
| | std::nth_element(elements_begin, elements_begin + m, elements_end, compare); |
| |
|
| | |
| | if (m > 0) { |
| | child_[2*index + 0] = MakeBVH(elements_begin, elements_begin + m, lev + 1); |
| | } |
| |
|
| | if (m != nelements) { |
| | child_[2*index + 1] = MakeBVH(elements_begin + m, elements_end, lev + 1); |
| | } |
| |
|
| | |
| | if (child_[2*index + 0] == -1 && child_[2*index + 1] == -1) { |
| | mju_error("this should have been a leaf, body=%s nelements=%d", |
| | name_.c_str(), nelements); |
| | } |
| |
|
| | if (lev > mjMAXTREEDEPTH) { |
| | mju_warning("max tree depth exceeded in body=%s", name_.c_str()); |
| | } |
| |
|
| | return index; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | void mjCOctree::SetFace(const std::vector<double>& vert, const std::vector<int>& face) { |
| | for (int i = 0; i < face.size(); i += 3) { |
| | std::array<double, 3> v0 = {vert[3*face[i+0]], vert[3*face[i+0]+1], vert[3*face[i+0]+2]}; |
| | std::array<double, 3> v1 = {vert[3*face[i+1]], vert[3*face[i+1]+1], vert[3*face[i+1]+2]}; |
| | std::array<double, 3> v2 = {vert[3*face[i+2]], vert[3*face[i+2]+1], vert[3*face[i+2]+2]}; |
| | face_.push_back({v0, v1, v2}); |
| | } |
| | } |
| |
|
| |
|
| | |
| | void mjCOctree::Make(std::vector<Triangle>& elements) { |
| | |
| | elements.assign(face_.size(), {{{0}}}); |
| | double qinv[4] = {iquat_[0], -iquat_[1], -iquat_[2], -iquat_[3]}; |
| | for (int i = 0; i < face_.size(); i++) { |
| | for (int j = 0; j < 3; j++) { |
| | double vert[3] = {face_[i][j][0] - ipos_[0], |
| | face_[i][j][1] - ipos_[1], |
| | face_[i][j][2] - ipos_[2]}; |
| | mjuu_rotVecQuat(elements[i][j].data(), vert, qinv); |
| | } |
| | } |
| | } |
| |
|
| |
|
| | void mjCOctree::CreateOctree(const double aamm[6]) { |
| | double aabb[6] = {(aamm[0] + aamm[3]) / 2, (aamm[1] + aamm[4]) / 2, (aamm[2] + aamm[5]) / 2, |
| | (aamm[3] - aamm[0]) / 2, (aamm[4] - aamm[1]) / 2, (aamm[5] - aamm[2]) / 2}; |
| | double box[6] = {aabb[0] - 1.1 * aabb[3], aabb[1] - 1.1 * aabb[4], aabb[2] - 1.1 * aabb[5], |
| | aabb[0] + 1.1 * aabb[3], aabb[1] + 1.1 * aabb[4], aabb[2] + 1.1 * aabb[5]}; |
| | std::vector<Triangle> elements; |
| | Make(elements); |
| | std::vector<Triangle*> elements_ptrs(elements.size()); |
| | std::transform(elements.begin(), elements.end(), elements_ptrs.begin(), |
| | [](Triangle& triangle) { return ▵ }); |
| | MakeOctree(elements_ptrs, box); |
| | } |
| |
|
| |
|
| | static bool boxTriangle(const Triangle& element, const double aamm[6]) { |
| | for (int i = 0; i < 3; i++) { |
| | if (element[0][i] < aamm[i] && element[1][i] < aamm[i] && element[2][i] < aamm[i]) { |
| | return false; |
| | } |
| | int j = i + 3; |
| | if (element[0][i] > aamm[j] && element[1][i] > aamm[j] && element[2][i] > aamm[j]) { |
| | return false; |
| | } |
| | } |
| | |
| | return true; |
| | } |
| |
|
| |
|
| | int mjCOctree::MakeOctree(const std::vector<Triangle*>& elements, const double aamm[6], int lev) { |
| | level_.push_back(lev); |
| |
|
| | |
| | int index = nnode_++; |
| | double aabb[6] = {(aamm[0] + aamm[3]) / 2, (aamm[1] + aamm[4]) / 2, (aamm[2] + aamm[5]) / 2, |
| | (aamm[3] - aamm[0]) / 2, (aamm[4] - aamm[1]) / 2, (aamm[5] - aamm[2]) / 2}; |
| | for (int i = 0; i < 6; i++) { |
| | node_.push_back(aabb[i]); |
| | } |
| | for (int i = 0; i < 8; i++) { |
| | child_.push_back(-1); |
| | } |
| |
|
| | |
| | std::vector<Triangle*> colliding; |
| | for (auto* element : elements) { |
| | if (boxTriangle(*element, aamm)) { |
| | colliding.push_back(element); |
| | } |
| | } |
| |
|
| | |
| | if (colliding.empty() || lev >= 6) { |
| | return index; |
| | } |
| |
|
| | |
| | double new_aamm[8][6]; |
| | for (int i = 0; i < 8; i++) { |
| | new_aamm[i][0] = aabb[0] + aabb[3] * (i & 1 ? -1 : 0); |
| | new_aamm[i][1] = aabb[1] + aabb[4] * (i & 2 ? -1 : 0); |
| | new_aamm[i][2] = aabb[2] + aabb[5] * (i & 4 ? -1 : 0); |
| | new_aamm[i][3] = aabb[0] + aabb[3] * (i & 1 ? 0 : 1); |
| | new_aamm[i][4] = aabb[1] + aabb[4] * (i & 2 ? 0 : 1); |
| | new_aamm[i][5] = aabb[2] + aabb[5] * (i & 4 ? 0 : 1); |
| | } |
| |
|
| | |
| | for (int i = 0; i < 8; i++) { |
| | child_[8*index + i] = MakeOctree(colliding, new_aamm[i], lev + 1); |
| | } |
| |
|
| | return index; |
| | } |
| |
|
| | |
| |
|
| | |
| | mjCDef::mjCDef() { |
| | name.clear(); |
| | id = 0; |
| | parent = nullptr; |
| | model = 0; |
| | child.clear(); |
| | elemtype = mjOBJ_DEFAULT; |
| | mjs_defaultJoint(&joint_.spec); |
| | mjs_defaultGeom(&geom_.spec); |
| | mjs_defaultSite(&site_.spec); |
| | mjs_defaultCamera(&camera_.spec); |
| | mjs_defaultLight(&light_.spec); |
| | mjs_defaultFlex(&flex_.spec); |
| | mjs_defaultMesh(&mesh_.spec); |
| | mjs_defaultMaterial(&material_.spec); |
| | mjs_defaultPair(&pair_.spec); |
| | mjs_defaultEquality(&equality_.spec); |
| | mjs_defaultTendon(&tendon_.spec); |
| | mjs_defaultActuator(&actuator_.spec); |
| |
|
| | |
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCDef::mjCDef(mjCModel* _model) : mjCDef() { |
| | model = _model; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCDef::mjCDef(const mjCDef& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCDef::Compile(const mjCModel* model) { |
| | CopyFromSpec(); |
| |
|
| | |
| | joint_.userdata_.resize(model->nuser_jnt); |
| | geom_.userdata_.resize(model->nuser_geom); |
| | site_.userdata_.resize(model->nuser_site); |
| | camera_.userdata_.resize(model->nuser_cam); |
| | tendon_.userdata_.resize(model->nuser_tendon); |
| | actuator_.userdata_.resize(model->nuser_actuator); |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCDef& mjCDef::operator=(const mjCDef& other) { |
| | if (this != &other) { |
| | CopyWithoutChildren(other); |
| |
|
| | |
| | *this += other; |
| | } |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | mjCDef& mjCDef::operator+=(const mjCDef& other) { |
| | for (unsigned int i=0; i < other.child.size(); i++) { |
| | child.push_back(new mjCDef(*other.child[i])); |
| | child.back()->parent = this; |
| | } |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCDef::NameSpace(const mjCModel* m) { |
| | if (!name.empty()) { |
| | name = m->prefix + name + m->suffix; |
| | } |
| | for (auto c : child) { |
| | c->NameSpace(m); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCDef::CopyWithoutChildren(const mjCDef& other) { |
| | name = other.name; |
| | elemtype = other.elemtype; |
| | parent = nullptr; |
| | child.clear(); |
| | joint_ = other.joint_; |
| | geom_ = other.geom_; |
| | site_ = other.site_; |
| | camera_ = other.camera_; |
| | light_ = other.light_; |
| | flex_ = other.flex_; |
| | mesh_ = other.mesh_; |
| | material_ = other.material_; |
| | pair_ = other.pair_; |
| | equality_ = other.equality_; |
| | tendon_ = other.tendon_; |
| | actuator_ = other.actuator_; |
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | void mjCDef::PointToLocal() { |
| | joint_.PointToLocal(); |
| | geom_.PointToLocal(); |
| | site_.PointToLocal(); |
| | camera_.PointToLocal(); |
| | light_.PointToLocal(); |
| | flex_.PointToLocal(); |
| | mesh_.PointToLocal(); |
| | material_.PointToLocal(); |
| | pair_.PointToLocal(); |
| | equality_.PointToLocal(); |
| | tendon_.PointToLocal(); |
| | actuator_.PointToLocal(); |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.joint = &joint_.spec; |
| | spec.geom = &geom_.spec; |
| | spec.site = &site_.spec; |
| | spec.camera = &camera_.spec; |
| | spec.light = &light_.spec; |
| | spec.flex = &flex_.spec; |
| | spec.mesh = &mesh_.spec; |
| | spec.material = &material_.spec; |
| | spec.pair = &pair_.spec; |
| | spec.equality = &equality_.spec; |
| | spec.tendon = &tendon_.spec; |
| | spec.actuator = &actuator_.spec; |
| | } |
| |
|
| |
|
| |
|
| | void mjCDef::CopyFromSpec() { |
| | joint_.CopyFromSpec(); |
| | geom_.CopyFromSpec(); |
| | site_.CopyFromSpec(); |
| | camera_.CopyFromSpec(); |
| | light_.CopyFromSpec(); |
| | flex_.CopyFromSpec(); |
| | mesh_.CopyFromSpec(); |
| | material_.CopyFromSpec(); |
| | pair_.CopyFromSpec(); |
| | equality_.CopyFromSpec(); |
| | tendon_.CopyFromSpec(); |
| | actuator_.CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCBase::mjCBase() { |
| | name.clear(); |
| | classname.clear(); |
| | id = -1; |
| | info = ""; |
| | model = 0; |
| | frame = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | mjCBase::mjCBase(const mjCBase& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCBase& mjCBase::operator=(const mjCBase& other) { |
| | if (this != &other) { |
| | *static_cast<mjCBase_*>(this) = static_cast<const mjCBase_&>(other); |
| | } |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBase::NameSpace(const mjCModel* m) { |
| | if (!name.empty()) { |
| | name = m->prefix + name + m->suffix; |
| | } |
| | if (!classname.empty() && classname != "main" && m != model) { |
| | classname = m->prefix + classname + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjResource* mjCBase::LoadResource(const std::string& modelfiledir, |
| | const std::string& filename, |
| | const mjVFS* vfs) { |
| | |
| | std::array<char, 1024> error; |
| | mjResource* resource = mju_openResource(modelfiledir.c_str(), filename.c_str(), vfs, |
| | error.data(), error.size()); |
| | if (!resource) { |
| | throw mjCError(nullptr, "%s", error.data()); |
| | } |
| | return resource; |
| | } |
| |
|
| |
|
| | |
| | |
| | std::string mjCBase::GetAssetContentType(std::string_view resource_name, |
| | std::string_view raw_text) { |
| | if (!raw_text.empty()) { |
| | auto type = mjuu_parseContentTypeAttrType(raw_text); |
| | auto subtype = mjuu_parseContentTypeAttrSubtype(raw_text); |
| | if (!type.has_value() || !subtype.has_value()) { |
| | return ""; |
| | } |
| | return std::string(*type) + "/" + std::string(*subtype); |
| | } else { |
| | return mjuu_extToContentType(resource_name); |
| | } |
| | } |
| |
|
| |
|
| | void mjCBase::SetFrame(mjCFrame* _frame) { |
| | if (!_frame) { |
| | return; |
| | } |
| | if (_frame->body && GetParent() != _frame->body) { |
| | throw mjCError(this, "Frame and body '%s' have mismatched parents", name.c_str()); |
| | } |
| | frame = _frame; |
| | } |
| |
|
| | void mjCBase::SetUserValue(std::string_view key, const void* data, |
| | void (*cleanup)(const void*)) { |
| | user_payload_[std::string(key)] = UserValue(data, cleanup); |
| | } |
| |
|
| | const void* mjCBase::GetUserValue(std::string_view key) { |
| | auto found = user_payload_.find(std::string(key)); |
| | return found != user_payload_.end() ? found->second.value : nullptr; |
| | } |
| |
|
| |
|
| | void mjCBase::DeleteUserValue(std::string_view key) { |
| | user_payload_.erase(std::string(key)); |
| | } |
| |
|
| |
|
| | |
| |
|
| | |
| | mjCBody::mjCBody(mjCModel* _model) { |
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | refcount = 1; |
| | mjs_defaultBody(&spec); |
| | elemtype = mjOBJ_BODY; |
| | parent = nullptr; |
| | weldid = -1; |
| | dofnum = 0; |
| | lastdof = -1; |
| | subtreedofs = 0; |
| | contype = 0; |
| | conaffinity = 0; |
| | margin = 0; |
| | mjuu_zerovec(xpos0, 3); |
| | mjuu_setvec(xquat0, 1, 0, 0, 0); |
| | last_attached = nullptr; |
| | mocapid = -1; |
| |
|
| | |
| | bodies.clear(); |
| | geoms.clear(); |
| | frames.clear(); |
| | joints.clear(); |
| | sites.clear(); |
| | cameras.clear(); |
| | lights.clear(); |
| | spec_userdata_.clear(); |
| |
|
| | |
| | CopyFromSpec(); |
| |
|
| | |
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | mjCBody::mjCBody(const mjCBody& other, mjCModel* _model) { |
| | model = _model; |
| | mjSpec* origin = model->FindSpec(other.compiler); |
| | compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | *this = other; |
| | CopyPlugin(); |
| | } |
| |
|
| |
|
| |
|
| | mjCBody& mjCBody::operator=(const mjCBody& other) { |
| | if (this != &other) { |
| | spec = other.spec; |
| | *static_cast<mjCBody_*>(this) = static_cast<const mjCBody_&>(other); |
| | *static_cast<mjsBody*>(this) = static_cast<const mjsBody&>(other); |
| | bodies.clear(); |
| | frames.clear(); |
| | geoms.clear(); |
| | joints.clear(); |
| | sites.clear(); |
| | cameras.clear(); |
| | lights.clear(); |
| | id = -1; |
| | subtreedofs = 0; |
| |
|
| | |
| | *this += other; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBody& mjCBody::operator+=(const mjCBody& other) { |
| | |
| | std::map<mjCFrame*, int> fmap; |
| | for (int i=0; i < other.frames.size(); i++) { |
| | fmap[other.frames[i]] = i + frames.size(); |
| | } |
| |
|
| | |
| | CopyList(frames, other.frames, fmap); |
| |
|
| | |
| | CopyList(geoms, other.geoms, fmap); |
| | CopyList(joints, other.joints, fmap); |
| | CopyList(sites, other.sites, fmap); |
| | CopyList(cameras, other.cameras, fmap); |
| | CopyList(lights, other.lights, fmap); |
| |
|
| | for (int i=0; i < other.bodies.size(); i++) { |
| | bodies.push_back(new mjCBody(*other.bodies[i], model)); |
| | bodies.back()->parent = this; |
| | bodies.back()->frame = nullptr; |
| | if (other.bodies[i]->frame) { |
| | if (fmap.find(other.bodies[i]->frame) != fmap.end()) { |
| | bodies.back()->frame = frames[fmap[other.bodies[i]->frame]]; |
| | } else { |
| | throw mjCError(this, "Frame '%s' not found in other body", |
| | other.bodies[i]->frame->name.c_str()); |
| | } |
| | if (bodies.back()->frame && bodies.back()->frame->body != this) { |
| | throw mjCError(this, "Frame and body '%s' have mismatched parents", name.c_str()); |
| | } |
| | } |
| | } |
| |
|
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBody& mjCBody::operator+=(const mjCFrame& other) { |
| | |
| | if (other.model != model && !model->FindSpec(&other.model->spec.compiler)) { |
| | model->AppendSpec(mj_copySpec(&other.model->spec), &other.model->spec.compiler); |
| | } |
| |
|
| | |
| | mjCBody* subtree = other.body; |
| | other.model->prefix = other.prefix; |
| | other.model->suffix = other.suffix; |
| | other.model->StoreKeyframes(model); |
| | mjCModel* other_model = other.model; |
| |
|
| | |
| | if (other_model != model) { |
| | mjCDef* subdef = new mjCDef(*other_model->Default()); |
| | subdef->NameSpace(other_model); |
| | *model += *subdef; |
| | } |
| |
|
| | |
| | mjSpec* origin = model->FindSpec(other.compiler); |
| | mjCFrame* newframe(model->deepcopy_ ? new mjCFrame(other) : (mjCFrame*)&other); |
| | frames.push_back(newframe); |
| | frames.back()->body = this; |
| | frames.back()->model = model; |
| | frames.back()->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | frames.back()->frame = other.frame; |
| | if (model->deepcopy_) { |
| | frames.back()->NameSpace(other_model); |
| | } else { |
| | frames.back()->AddRef(); |
| | } |
| | int i = frames.size(); |
| | last_attached = &frames.back()->spec; |
| |
|
| | |
| | std::map<mjCFrame*, int> fmap; |
| | for (auto frame : subtree->frames) { |
| | if (frame == static_cast<const mjCFrame*>(&other)) { |
| | fmap[frame] = frames.size() - 1; |
| | } else if (other.IsAncestor(frame)) { |
| | fmap[frame] = i++; |
| | } |
| | } |
| |
|
| | |
| | CopyList(frames, subtree->frames, fmap, &other); |
| | CopyList(geoms, subtree->geoms, fmap, &other); |
| | CopyList(joints, subtree->joints, fmap, &other); |
| | CopyList(sites, subtree->sites, fmap, &other); |
| | CopyList(cameras, subtree->cameras, fmap, &other); |
| | CopyList(lights, subtree->lights, fmap, &other); |
| |
|
| | if (!model->deepcopy_) { |
| | std::string name = subtree->name; |
| | subtree->SetModel(model); |
| | subtree->NameSpace(other_model); |
| | subtree->name = name; |
| | } |
| |
|
| | int nbodies = (int)subtree->bodies.size(); |
| | for (int i=0; i < nbodies; i++) { |
| | if (!other.IsAncestor(subtree->bodies[i]->frame)) { |
| | continue; |
| | } |
| | if (model->deepcopy_) { |
| | mjCBody* newbody(new mjCBody(*subtree->bodies[i], model)); |
| | bodies.push_back(newbody); |
| | subtree->bodies[i]->ForgetKeyframes(); |
| | bodies.back()->NameSpace_(other_model, false); |
| | } else { |
| | bodies.push_back(subtree->bodies[i]); |
| | bodies.back()->SetModel(model); |
| | bodies.back()->ResetId(); |
| | bodies.back()->AddRef(); |
| | } |
| | bodies.back()->parent = this; |
| | bodies.back()->frame = |
| | subtree->bodies[i]->frame ? frames[fmap[subtree->bodies[i]->frame]] : nullptr; |
| | } |
| |
|
| | |
| | other_model->SetAttached(model->deepcopy_); |
| | *model += *other_model; |
| |
|
| | |
| | if (other_model != model) { |
| | other_model->key_pending_.clear(); |
| | } |
| |
|
| | |
| | other_model->prefix.clear(); |
| | other_model->suffix.clear(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | template <typename T> |
| | void mjCBody::CopyList(std::vector<T*>& dst, const std::vector<T*>& src, |
| | std::map<mjCFrame*, int>& fmap, const mjCFrame* pframe) { |
| | int nsrc = (int)src.size(); |
| | int ndst = (int)dst.size(); |
| | for (int i=0; i < nsrc; i++) { |
| | if (pframe && !pframe->IsAncestor(src[i]->frame)) { |
| | continue; |
| | } |
| | mjSpec* origin = model->FindSpec(src[i]->compiler); |
| | T* new_obj = model->deepcopy_ ? new T(*src[i]) : src[i]; |
| | dst.push_back(new_obj); |
| | dst.back()->body = this; |
| | dst.back()->model = model; |
| | dst.back()->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | dst.back()->id = -1; |
| | dst.back()->CopyPlugin(); |
| | dst.back()->classname = src[i]->classname; |
| |
|
| | |
| | if (!model->deepcopy_) { |
| | dst.back()->AddRef(); |
| | } |
| |
|
| | |
| | dst.back()->NameSpace(src[i]->model); |
| | } |
| |
|
| | |
| | |
| | int j = 0; |
| | for (int i = 0; i < src.size(); i++) { |
| | if (pframe && !pframe->IsAncestor(src[i]->frame)) { |
| | continue; |
| | } |
| | dst[ndst + j++]->frame = src[i]->frame ? frames[fmap[src[i]->frame]] : nullptr; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBody& mjCBody::operator-=(const mjCBody& subtree) { |
| | for (int i=0; i < bodies.size(); i++) { |
| | if (bodies[i] == &subtree) { |
| | bodies.erase(bodies.begin() + i); |
| | break; |
| | } |
| | *bodies[i] -= subtree; |
| | } |
| |
|
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::SetModel(mjCModel* _model) { |
| | model = _model; |
| | mjSpec* origin = _model->FindSpec(compiler); |
| | compiler = origin ? &origin->compiler : &model->spec.compiler; |
| |
|
| | for (auto& body : bodies) { |
| | body->SetModel(_model); |
| | } |
| | for (auto& frame : frames) { |
| | origin = _model->FindSpec(frame->compiler); |
| | frame->model = _model; |
| | frame->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | for (auto& geom : geoms) { |
| | origin = _model->FindSpec(geom->compiler); |
| | geom->model = _model; |
| | geom->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | for (auto& joint : joints) { |
| | origin = _model->FindSpec(joint->compiler); |
| | joint->model = _model; |
| | joint->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | for (auto& site : sites) { |
| | origin = _model->FindSpec(site->compiler); |
| | site->model = _model; |
| | site->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | for (auto& camera : cameras) { |
| | origin = _model->FindSpec(camera->compiler); |
| | camera->model = _model; |
| | camera->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | for (auto& light : lights) { |
| | origin = _model->FindSpec(light->compiler); |
| | light->model = _model; |
| | light->compiler = origin ? &origin->compiler : &model->spec.compiler; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::ResetId() { |
| | id = -1; |
| | for (auto& body : bodies) { |
| | body->ResetId(); |
| | } |
| | for (auto& frame : frames) { |
| | frame->id = -1; |
| | } |
| | for (auto& geom : geoms) { |
| | geom->id = -1; |
| | } |
| | for (auto& joint : joints) { |
| | joint->id = -1; |
| | joint->qposadr_ = -1; |
| | joint->dofadr_ = -1; |
| | } |
| | for (auto& site : sites) { |
| | site->id = -1; |
| | } |
| | for (auto& camera : cameras) { |
| | camera->id = -1; |
| | } |
| | for (auto& light : lights) { |
| | light->id = -1; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCBody::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.childclass = &classname; |
| | spec.userdata = &spec_userdata_; |
| | spec.plugin.plugin_name = &plugin_name; |
| | spec.plugin.name = (&plugin_instance_name); |
| | spec.info = &info; |
| | userdata = nullptr; |
| | } |
| |
|
| |
|
| | void mjCBody::CopyFromSpec() { |
| | *static_cast<mjsBody*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | plugin.active = spec.plugin.active; |
| | plugin.element = spec.plugin.element; |
| | plugin.plugin_name = spec.plugin.plugin_name; |
| | plugin.name = spec.plugin.name; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBody::CopyPlugin() { |
| | model->CopyExplicitPlugin(this); |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBody::~mjCBody() { |
| | for (int i=0; i < bodies.size(); i++) bodies[i]->Release(); |
| | for (int i=0; i < geoms.size(); i++) geoms[i]->Release(); |
| | for (int i=0; i < frames.size(); i++) frames[i]->Release(); |
| | for (int i=0; i < joints.size(); i++) joints[i]->Release(); |
| | for (int i=0; i < sites.size(); i++) sites[i]->Release(); |
| | for (int i=0; i < cameras.size(); i++) cameras[i]->Release(); |
| | for (int i=0; i < lights.size(); i++) lights[i]->Release(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::NameSpace(const mjCModel* m) { |
| | NameSpace_(m, true); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::NameSpace_(const mjCModel* m, bool propagate) { |
| | mjCBase::NameSpace(m); |
| | if (!plugin_instance_name.empty()) { |
| | plugin_instance_name = m->prefix + plugin_instance_name + m->suffix; |
| | } |
| |
|
| | for (auto& body : bodies) { |
| | body->prefix = m->prefix; |
| | body->suffix = m->suffix; |
| | body->NameSpace_(m, propagate); |
| | } |
| |
|
| | if (!propagate) { |
| | return; |
| | } |
| |
|
| | for (auto& joint : joints) { |
| | joint->NameSpace(m); |
| | } |
| |
|
| | for (auto& geom : geoms) { |
| | geom->NameSpace(m); |
| | } |
| |
|
| | for (auto& site : sites) { |
| | site->NameSpace(m); |
| | } |
| |
|
| | for (auto& camera : cameras) { |
| | camera->NameSpace(m); |
| | } |
| |
|
| | for (auto& light : lights) { |
| | light->NameSpace(m); |
| | } |
| |
|
| | for (auto& frame : frames) { |
| | frame->NameSpace(m); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBody* mjCBody::AddBody(mjCDef* _def) { |
| | |
| | mjCBody* obj = new mjCBody(model); |
| |
|
| | |
| | obj->classname = _def ? _def->name : classname; |
| |
|
| | bodies.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | obj->parent = this; |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCFrame* mjCBody::AddFrame(mjCFrame* _frame) { |
| | mjCFrame* obj = new mjCFrame(model, _frame ? _frame : NULL); |
| | frames.push_back(obj); |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCJoint* mjCBody::AddFreeJoint() { |
| | |
| | mjCJoint* obj = new mjCJoint(model, NULL); |
| | obj->spec.type = mjJNT_FREE; |
| |
|
| | |
| | obj->body = this; |
| |
|
| | joints.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCJoint* mjCBody::AddJoint(mjCDef* _def) { |
| | |
| | mjCJoint* obj = new mjCJoint(model, _def ? _def : model->def_map[classname]); |
| |
|
| | |
| | obj->body = this; |
| |
|
| | joints.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCGeom* mjCBody::AddGeom(mjCDef* _def) { |
| | |
| | mjCGeom* obj = new mjCGeom(model, _def ? _def : model->def_map[classname]); |
| |
|
| | |
| | obj->body = this; |
| |
|
| | geoms.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCSite* mjCBody::AddSite(mjCDef* _def) { |
| | |
| | mjCSite* obj = new mjCSite(model, _def ? _def : model->def_map[classname]); |
| |
|
| | |
| | obj->body = this; |
| |
|
| | sites.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCCamera* mjCBody::AddCamera(mjCDef* _def) { |
| | |
| | mjCCamera* obj = new mjCCamera(model, _def ? _def : model->def_map[classname]); |
| |
|
| | |
| | obj->body = this; |
| |
|
| | cameras.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCLight* mjCBody::AddLight(mjCDef* _def) { |
| | |
| | mjCLight* obj = new mjCLight(model, _def ? _def : model->def_map[classname]); |
| |
|
| | |
| | obj->body = this; |
| |
|
| | lights.push_back(obj); |
| |
|
| | |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| |
|
| | |
| | model->spec.element->signature = model->Signature(); |
| | return obj; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCFrame* mjCBody::ToFrame() { |
| | mjCFrame* newframe = parent->AddFrame(frame); |
| | mjuu_copyvec(newframe->spec.pos, spec.pos, 3); |
| | mjuu_copyvec(newframe->spec.quat, spec.quat, 4); |
| | if (parent->name != "world" && mass >= mjMINVAL) { |
| | if (!parent->explicitinertial) { |
| | parent->MakeInertialExplicit(); |
| | mjuu_zerovec(parent->spec.ipos, 3); |
| | mjuu_zerovec(parent->spec.iquat, 4); |
| | mjuu_zerovec(parent->spec.inertia, 3); |
| | } |
| | parent->AccumulateInertia(&this->spec, &parent->spec); |
| | } |
| | MapFrame(parent->bodies, bodies, newframe, parent); |
| | MapFrame(parent->geoms, geoms, newframe, parent); |
| | MapFrame(parent->joints, joints, newframe, parent); |
| | MapFrame(parent->sites, sites, newframe, parent); |
| | MapFrame(parent->cameras, cameras, newframe, parent); |
| | MapFrame(parent->lights, lights, newframe, parent); |
| | MapFrame(parent->frames, frames, newframe, parent); |
| | parent->bodies.erase( |
| | std::remove_if(parent->bodies.begin(), parent->bodies.end(), |
| | [this](mjCBody* body) { return body == this; }), |
| | parent->bodies.end()); |
| | model->ResetTreeLists(); |
| | model->MakeTreeLists(); |
| | model->spec.element->signature = model->Signature(); |
| | return newframe; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjCBody::NumObjects(mjtObj type) { |
| | switch (type) { |
| | case mjOBJ_BODY: |
| | case mjOBJ_XBODY: |
| | return (int)bodies.size(); |
| | case mjOBJ_JOINT: |
| | return (int)joints.size(); |
| | case mjOBJ_GEOM: |
| | return (int)geoms.size(); |
| | case mjOBJ_SITE: |
| | return (int)sites.size(); |
| | case mjOBJ_CAMERA: |
| | return (int)cameras.size(); |
| | case mjOBJ_LIGHT: |
| | return (int)lights.size(); |
| | default: |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBase* mjCBody::GetObject(mjtObj type, int i) { |
| | if (i >= 0 && i < NumObjects(type)) { |
| | switch (type) { |
| | case mjOBJ_BODY: |
| | case mjOBJ_XBODY: |
| | return bodies[i]; |
| | case mjOBJ_JOINT: |
| | return joints[i]; |
| | case mjOBJ_GEOM: |
| | return geoms[i]; |
| | case mjOBJ_SITE: |
| | return sites[i]; |
| | case mjOBJ_CAMERA: |
| | return cameras[i]; |
| | case mjOBJ_LIGHT: |
| | return lights[i]; |
| | default: |
| | return 0; |
| | } |
| | } |
| |
|
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | template <class T> |
| | static T* findobject(std::string name, std::vector<T*>& list) { |
| | for (unsigned int i=0; i < list.size(); i++) { |
| | if (list[i]->name == name) { |
| | return list[i]; |
| | } |
| | } |
| |
|
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCBase* mjCBody::FindObject(mjtObj type, std::string _name, bool recursive) { |
| | mjCBase* res = 0; |
| |
|
| | |
| | if (name == _name) { |
| | return this; |
| | } |
| |
|
| | |
| | if (type == mjOBJ_BODY || type == mjOBJ_XBODY) { |
| | res = findobject(_name, bodies); |
| | } else if (type == mjOBJ_JOINT) { |
| | res = findobject(_name, joints); |
| | } else if (type == mjOBJ_GEOM) { |
| | res = findobject(_name, geoms); |
| | } else if (type == mjOBJ_SITE) { |
| | res = findobject(_name, sites); |
| | } else if (type == mjOBJ_CAMERA) { |
| | res = findobject(_name, cameras); |
| | } else if (type == mjOBJ_LIGHT) { |
| | res = findobject(_name, lights); |
| | } |
| |
|
| | |
| | if (res) { |
| | return res; |
| | } |
| |
|
| | |
| | if (recursive) { |
| | for (int i=0; i < (int)bodies.size(); i++) { |
| | if ((res = bodies[i]->FindObject(type, _name, true))) { |
| | return res; |
| | } |
| | } |
| | } |
| |
|
| | |
| | return res; |
| | } |
| |
|
| |
|
| |
|
| | |
| | bool mjCBody::IsAncestor(const mjCBody* child) const { |
| | if (!child) { |
| | return false; |
| | } |
| |
|
| | if (child == this) { |
| | return true; |
| | } |
| |
|
| | return IsAncestor(child->parent); |
| | } |
| |
|
| |
|
| |
|
| | template <class T> |
| | mjsElement* mjCBody::GetNext(const std::vector<T*>& list, const mjsElement* child) { |
| | if (list.empty()) { |
| | |
| | return nullptr; |
| | } |
| |
|
| | for (unsigned int i = 0; i < list.size() - (child ? 1 : 0); i++) { |
| | if (!IsAncestor(list[i]->GetParent())) { |
| | continue; |
| | } |
| |
|
| | |
| | if (!child) { |
| | return list[i]->spec.element; |
| |
|
| | |
| | } else if (list[i]->spec.element == child && IsAncestor(list[i+1]->GetParent())) { |
| | return list[i+1]->spec.element; |
| | } |
| | } |
| |
|
| | return nullptr; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjsElement* mjCBody::NextChild(const mjsElement* child, mjtObj type, bool recursive) { |
| | if (type == mjOBJ_UNKNOWN) { |
| | if (!child) { |
| | throw mjCError(this, "child type must be specified if no child element is given"); |
| | } else { |
| | type = child->elemtype; |
| | } |
| | } else if (child && child->elemtype != type) { |
| | throw mjCError(this, "child element is not of requested type"); |
| | } |
| |
|
| |
|
| | mjsElement* candidate = nullptr; |
| | switch (type) { |
| | case mjOBJ_BODY: |
| | case mjOBJ_XBODY: |
| | candidate = GetNext(recursive ? model->bodies_ : bodies, child); |
| | break; |
| | case mjOBJ_JOINT: |
| | candidate = GetNext(recursive ? model->joints_ : joints, child); |
| | break; |
| | case mjOBJ_GEOM: |
| | candidate = GetNext(recursive ? model->geoms_ : geoms, child); |
| | break; |
| | case mjOBJ_SITE: |
| | candidate = GetNext(recursive ? model->sites_ : sites, child); |
| | break; |
| | case mjOBJ_CAMERA: |
| | candidate = GetNext(recursive ? model->cameras_ : cameras, child); |
| | break; |
| | case mjOBJ_LIGHT: |
| | candidate = GetNext(recursive ? model->lights_ : lights, child); |
| | break; |
| | case mjOBJ_FRAME: |
| | candidate = GetNext(recursive ? model->frames_ : frames, child); |
| | break; |
| | default: |
| | throw mjCError(this, |
| | "Body.NextChild supports the types: body, frame, geom, " |
| | "site, light, camera"); |
| | break; |
| | } |
| |
|
| | return candidate; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::InertiaFromGeom(void) { |
| | int sz; |
| | double com[3] = {0, 0, 0}; |
| | double toti[6] = {0, 0, 0, 0, 0, 0}; |
| | std::vector<mjCGeom*> sel; |
| |
|
| | |
| | sel.clear(); |
| | for (int i=0; i < geoms.size(); i++) { |
| | if (geoms[i]->group >= compiler->inertiagrouprange[0] && |
| | geoms[i]->group <= compiler->inertiagrouprange[1]) { |
| | sel.push_back(geoms[i]); |
| | } |
| | } |
| | sz = sel.size(); |
| |
|
| | |
| | if (sz == 1) { |
| | mjuu_copyvec(ipos, sel[0]->pos, 3); |
| | mjuu_copyvec(iquat, sel[0]->quat, 4); |
| | mass = sel[0]->mass_; |
| | mjuu_copyvec(inertia, sel[0]->inertia, 3); |
| | } |
| |
|
| | |
| | else if (sz > 1) { |
| | |
| | mass = 0; |
| | for (int i=0; i < sz; i++) { |
| | mass += sel[i]->mass_; |
| | com[0] += sel[i]->mass_ * sel[i]->pos[0]; |
| | com[1] += sel[i]->mass_ * sel[i]->pos[1]; |
| | com[2] += sel[i]->mass_ * sel[i]->pos[2]; |
| | } |
| |
|
| | |
| | if (mass < mjEPS) { |
| | throw mjCError(this, "body mass is too small, cannot compute center of mass"); |
| | } |
| |
|
| | |
| | ipos[0] = com[0]/mass; |
| | ipos[1] = com[1]/mass; |
| | ipos[2] = com[2]/mass; |
| |
|
| | |
| | for (int i=0; i < sz; i++) { |
| | double inert0[6], inert1[6]; |
| | double dpos[3] = { |
| | sel[i]->pos[0] - ipos[0], |
| | sel[i]->pos[1] - ipos[1], |
| | sel[i]->pos[2] - ipos[2] |
| | }; |
| |
|
| | mjuu_globalinertia(inert0, sel[i]->inertia, sel[i]->quat); |
| | mjuu_offcenter(inert1, sel[i]->mass_, dpos); |
| | for (int j=0; j < 6; j++) { |
| | toti[j] = toti[j] + inert0[j] + inert1[j]; |
| | } |
| | } |
| |
|
| | |
| | mjuu_copyvec(fullinertia, toti, 6); |
| | const char* errq = mjuu_fullInertia(iquat, inertia, fullinertia); |
| | if (errq) { |
| | throw mjCError(this, "error '%s' in alternative for principal axes", errq); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::MakeInertialExplicit() { |
| | spec.explicitinertial = true; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::AccumulateInertia(const mjsBody* other, mjsBody* result) { |
| | if (!result) { |
| | result = this; |
| | } |
| |
|
| | |
| | double other_ipos[3]; |
| | double other_iquat[4]; |
| | mjuu_copyvec(other_ipos, other->ipos, 3); |
| | mjuu_copyvec(other_iquat, other->iquat, 4); |
| | mjuu_frameaccum(other_ipos, other_iquat, other->pos, other->quat); |
| |
|
| | |
| | double mass[2] = { |
| | result->mass, |
| | other->mass |
| | }; |
| | double inertia[2][3] = { |
| | {result->inertia[0], result->inertia[1], result->inertia[2]}, |
| | {other->inertia[0], other->inertia[1], other->inertia[2]} |
| | }; |
| | double ipos[2][3] = { |
| | {result->ipos[0], result->ipos[1], result->ipos[2]}, |
| | {other_ipos[0], other_ipos[1], other_ipos[2]} |
| | }; |
| | double iquat[2][4] = { |
| | {result->iquat[0], result->iquat[1], result->iquat[2], result->iquat[3]}, |
| | {other->iquat[0], other->iquat[1], other->iquat[2], other->iquat[3]} |
| | }; |
| |
|
| | |
| | result->mass = 0; |
| | mjuu_setvec(result->ipos, 0, 0, 0); |
| | for (int j=0; j < 2; j++) { |
| | result->mass += mass[j]; |
| | result->ipos[0] += mass[j]*ipos[j][0]; |
| | result->ipos[1] += mass[j]*ipos[j][1]; |
| | result->ipos[2] += mass[j]*ipos[j][2]; |
| | } |
| |
|
| | |
| | if (result->mass < mjMINVAL) { |
| | result->mass = 0; |
| | mjuu_setvec(result->inertia, 0, 0, 0); |
| | mjuu_setvec(result->ipos, 0, 0, 0); |
| | mjuu_setvec(result->iquat, 1, 0, 0, 0); |
| | } |
| |
|
| | |
| | else { |
| | |
| | result->ipos[0] /= result->mass; |
| | result->ipos[1] /= result->mass; |
| | result->ipos[2] /= result->mass; |
| |
|
| | |
| | double toti[6] = {0, 0, 0, 0, 0, 0}; |
| | for (int j=0; j < 2; j++) { |
| | double inertA[6], inertB[6]; |
| | double dpos[3] = { |
| | ipos[j][0] - result->ipos[0], |
| | ipos[j][1] - result->ipos[1], |
| | ipos[j][2] - result->ipos[2] |
| | }; |
| |
|
| | mjuu_globalinertia(inertA, inertia[j], iquat[j]); |
| | mjuu_offcenter(inertB, mass[j], dpos); |
| | for (int k=0; k < 6; k++) { |
| | toti[k] += inertA[k] + inertB[k]; |
| | } |
| | } |
| |
|
| | |
| | mjuu_copyvec(result->fullinertia, toti, 6); |
| | const char* err1 = mjuu_fullInertia(result->iquat, result->inertia, result->fullinertia); |
| | if (err1) { |
| | throw mjCError(nullptr, "error '%s' in fusing static body inertias", err1); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::ComputeBVH() { |
| | if (geoms.empty()) { |
| | return; |
| | } |
| |
|
| | tree.Set(ipos, iquat); |
| | tree.AllocateBoundingVolumes(geoms.size()); |
| | for (const mjCGeom* geom : geoms) { |
| | tree.AddBoundingVolume(&geom->id, geom->contype, geom->conaffinity, |
| | geom->pos, geom->quat, geom->aabb); |
| | } |
| | tree.CreateBVH(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::ForgetKeyframes() const { |
| | for (auto joint : joints) { |
| | joint->qpos_.clear(); |
| | joint->qvel_.clear(); |
| | } |
| | ((mjCBody*)this)->mpos_.clear(); |
| | ((mjCBody*)this)->mquat_.clear(); |
| | for (auto body : bodies) { |
| | body->ForgetKeyframes(); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | mjtNum* mjCBody::mpos(const std::string& state_name) { |
| | if (mpos_.find(state_name) == mpos_.end()) { |
| | mpos_[state_name] = {mjNAN, 0, 0}; |
| | } |
| | return mpos_.at(state_name).data(); |
| | } |
| |
|
| |
|
| |
|
| | mjtNum* mjCBody::mquat(const std::string& state_name) { |
| | if (mquat_.find(state_name) == mquat_.end()) { |
| | mquat_[state_name] = {mjNAN, 0, 0, 0}; |
| | } |
| | return mquat_.at(state_name).data(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBody::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | for (int i=0; i < frames.size(); i++) { |
| | frames[i]->Compile(); |
| | } |
| |
|
| | |
| | if (userdata_.size() > model->nuser_body) { |
| | throw mjCError(this, "user has more values than nuser_body in body"); |
| | } |
| | userdata_.resize(model->nuser_body); |
| |
|
| | |
| | mjuu_normvec(quat, 4); |
| | mjuu_normvec(iquat, 4); |
| |
|
| | |
| | for (int i=0; i < bodies.size(); i++) { |
| | bodies[i]->weldid = (!bodies[i]->joints.empty() ? bodies[i]->id : weldid); |
| | } |
| |
|
| | |
| | if (alt.type != mjORIENTATION_QUAT) { |
| | const char* err = ResolveOrientation(quat, compiler->degree, compiler->eulerseq, alt); |
| | if (err) { |
| | throw mjCError(this, "error '%s' in frame alternative", err); |
| | } |
| | } |
| |
|
| | |
| | if (mjuu_defined(fullinertia[0]) && ialt.type != mjORIENTATION_QUAT) { |
| | throw mjCError(this, "fullinertia and inertial orientation cannot both be specified"); |
| | } |
| | if (mjuu_defined(fullinertia[0]) && (inertia[0] || inertia[1] || inertia[2])) { |
| | throw mjCError(this, "fullinertia and diagonal inertia cannot both be specified"); |
| | } |
| |
|
| | |
| | if (mjuu_defined(fullinertia[0])) { |
| | const char* err = mjuu_fullInertia(iquat, inertia, this->fullinertia); |
| | if (err) { |
| | throw mjCError(this, "error '%s' in fullinertia", err); |
| | } |
| | } |
| |
|
| | if (ialt.type != mjORIENTATION_QUAT) { |
| | const char* err = ResolveOrientation(iquat, compiler->degree, compiler->eulerseq, ialt); |
| | if (err) { |
| | throw mjCError(this, "error '%s' in inertia alternative", err); |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < geoms.size(); i++) { |
| | geoms[i]->inferinertia = id > 0 && |
| | (!explicitinertial || compiler->inertiafromgeom == mjINERTIAFROMGEOM_TRUE) && |
| | geoms[i]->spec.group >= compiler->inertiagrouprange[0] && |
| | geoms[i]->spec.group <= compiler->inertiagrouprange[1]; |
| | geoms[i]->Compile(); |
| | } |
| |
|
| | |
| | if (id > 0 && (compiler->inertiafromgeom == mjINERTIAFROMGEOM_TRUE || |
| | (!mjuu_defined(ipos[0]) && compiler->inertiafromgeom == mjINERTIAFROMGEOM_AUTO))) { |
| | InertiaFromGeom(); |
| | } |
| |
|
| | |
| | if (!mjuu_defined(ipos[0])) { |
| | mjuu_copyvec(ipos, pos, 3); |
| | mjuu_copyvec(iquat, quat, 4); |
| | } |
| |
|
| | |
| | if (id > 0) { |
| | |
| | mass = std::max(mass, compiler->boundmass); |
| | inertia[0] = std::max(inertia[0], compiler->boundinertia); |
| | inertia[1] = std::max(inertia[1], compiler->boundinertia); |
| | inertia[2] = std::max(inertia[2], compiler->boundinertia); |
| |
|
| | |
| | if (mass < 0 || inertia[0] < 0 || inertia[1] < 0 ||inertia[2] < 0) { |
| | throw mjCError(this, "mass and inertia cannot be negative"); |
| | } |
| |
|
| | |
| | if (inertia[0] + inertia[1] < inertia[2] || |
| | inertia[0] + inertia[2] < inertia[1] || |
| | inertia[1] + inertia[2] < inertia[0]) { |
| | if (compiler->balanceinertia) { |
| | inertia[0] = inertia[1] = inertia[2] = (inertia[0] + inertia[1] + inertia[2])/3.0; |
| | } else { |
| | throw mjCError(this, "inertia must satisfy A + B >= C; use 'balanceinertia' to fix"); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (frame) { |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, quat); |
| | } |
| |
|
| | |
| | contype = conaffinity = 0; |
| | margin = 0; |
| | for (int i=0; i < geoms.size(); i++) { |
| | contype |= geoms[i]->contype; |
| | conaffinity |= geoms[i]->conaffinity; |
| | margin = std::max(margin, geoms[i]->margin); |
| | } |
| |
|
| | |
| | bool align_free = (joints.size() == 1 && |
| | joints[0]->spec.type == mjJNT_FREE && |
| | bodies.empty() && |
| | (joints[0]->spec.align == 1 || |
| | (joints[0]->spec.align == 2 && |
| | compiler->alignfree))); |
| |
|
| | |
| | double ipos_inverse[3], iquat_inverse[4]; |
| | if (align_free) { |
| | |
| | mjuu_frameaccum(pos, quat, ipos, iquat); |
| |
|
| | |
| | mjuu_frameinvert(ipos_inverse, iquat_inverse, ipos, iquat); |
| |
|
| | |
| | mjuu_setvec(ipos, 0, 0, 0); |
| | mjuu_setvec(iquat, 1, 0, 0, 0); |
| |
|
| | |
| | for (int i=0; i < geoms.size(); i++) { |
| | mjuu_frameaccumChild(ipos_inverse, iquat_inverse, geoms[i]->pos, geoms[i]->quat); |
| | } |
| | } |
| |
|
| | |
| | ComputeBVH(); |
| |
|
| | |
| | dofnum = 0; |
| | for (int i=0; i < joints.size(); i++) { |
| | dofnum += joints[i]->Compile(); |
| | } |
| |
|
| | |
| | if (dofnum > 6) { |
| | throw mjCError(this, "more than 6 dofs in body '%s'", name.c_str()); |
| | } |
| |
|
| | |
| | bool hasball = false; |
| | for (int i=0; i < joints.size(); i++) { |
| | if ((joints[i]->type == mjJNT_BALL || joints[i]->type == mjJNT_HINGE) && hasball) { |
| | throw mjCError(this, "ball followed by rotation in body '%s'", name.c_str()); |
| | } |
| | if (joints[i]->type == mjJNT_BALL) { |
| | hasball = true; |
| | } |
| | } |
| |
|
| | |
| | if (mocap && (dofnum || (parent && parent->name != "world"))) { |
| | throw mjCError(this, "mocap body '%s' is not a fixed child of world", name.c_str()); |
| | } |
| |
|
| | |
| | if (id > 0) { |
| | mjuu_rotVecQuat(xpos0, pos, parent->xquat0); |
| | mjuu_addtovec(xpos0, parent->xpos0, 3); |
| | mjuu_mulquat(xquat0, parent->xquat0, quat); |
| | } |
| |
|
| | |
| | for (int i=0; i < sites.size(); i++)sites[i]->Compile(); |
| |
|
| | |
| | for (int i=0; i < cameras.size(); i++)cameras[i]->Compile(); |
| |
|
| | |
| | for (int i=0; i < lights.size(); i++)lights[i]->Compile(); |
| |
|
| | |
| | if (plugin.active) { |
| | if (plugin_name.empty() && plugin_instance_name.empty()) { |
| | throw mjCError( |
| | this, "neither 'plugin' nor 'instance' is specified for body '%s', (id = %d)", |
| | name.c_str(), id); |
| | } |
| |
|
| | mjCPlugin* plugin_instance = static_cast<mjCPlugin*>(plugin.element); |
| | model->ResolvePlugin(this, plugin_name, plugin_instance_name, &plugin_instance); |
| | plugin.element = plugin_instance; |
| | const mjpPlugin* pplugin = mjp_getPluginAtSlot(plugin_instance->plugin_slot); |
| | if (!(pplugin->capabilityflags & mjPLUGIN_PASSIVE)) { |
| | throw mjCError(this, "plugin '%s' does not support passive forces", pplugin->name); |
| | } |
| | } |
| |
|
| | |
| | if (align_free) { |
| | |
| |
|
| | |
| | for (int i=0; i < sites.size(); i++) { |
| | mjuu_frameaccumChild(ipos_inverse, iquat_inverse, sites[i]->pos, sites[i]->quat); |
| | } |
| |
|
| | |
| | for (int i=0; i < cameras.size(); i++) { |
| | mjuu_frameaccumChild(ipos_inverse, iquat_inverse, cameras[i]->pos, cameras[i]->quat); |
| | } |
| |
|
| | |
| | for (int i=0; i < lights.size(); i++) { |
| | double qunit[4]= {1, 0, 0, 0}; |
| | mjuu_frameaccumChild(ipos_inverse, iquat_inverse, lights[i]->pos, qunit); |
| | mjuu_rotVecQuat(lights[i]->dir, lights[i]->dir, iquat_inverse); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCFrame::mjCFrame(mjCModel* _model, mjCFrame* _frame) { |
| | mjs_defaultFrame(&spec); |
| | elemtype = mjOBJ_FRAME; |
| | compiled = false; |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | body = NULL; |
| | frame = _frame ? _frame : NULL; |
| | last_attached = nullptr; |
| | PointToLocal(); |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCFrame::mjCFrame(const mjCFrame& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCFrame& mjCFrame::operator=(const mjCFrame& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCFrame_*>(this) = static_cast<const mjCFrame_&>(other); |
| | *static_cast<mjsFrame*>(this) = static_cast<const mjsFrame&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCFrame& mjCFrame::operator+=(const mjCBody& other) { |
| | |
| | if (other.model != model && !model->FindSpec(&other.model->spec.compiler)) { |
| | model->AppendSpec(mj_copySpec(&other.model->spec), &other.model->spec.compiler); |
| | } |
| |
|
| | |
| | other.model->prefix = other.prefix; |
| | other.model->suffix = other.suffix; |
| | other.model->StoreKeyframes(model); |
| | other.model->prefix = ""; |
| | other.model->suffix = ""; |
| | mjCModel* other_model = other.model; |
| |
|
| | |
| | mjCBody* subtree = model->deepcopy_ ? new mjCBody(other, model) : (mjCBody*)&other; |
| | if (model->deepcopy_) { |
| | other.ForgetKeyframes(); |
| | } else { |
| | subtree->SetModel(model); |
| | subtree->ResetId(); |
| | subtree->AddRef(); |
| | } |
| | other_model->prefix = subtree->prefix; |
| | other_model->suffix = subtree->suffix; |
| | subtree->SetParent(body); |
| | subtree->SetFrame(this); |
| | subtree->NameSpace(other_model); |
| |
|
| | |
| | if (other_model != model) { |
| | mjCDef* subdef = new mjCDef(*other_model->Default()); |
| | subdef->NameSpace(other_model); |
| | *model += *subdef; |
| | } |
| |
|
| | |
| | body->bodies.push_back(subtree); |
| | last_attached = &body->bodies.back()->spec; |
| |
|
| | |
| | other_model->SetAttached(model->deepcopy_); |
| | *model += *other_model; |
| |
|
| | |
| | if (other_model != model) { |
| | other_model->key_pending_.clear(); |
| | } |
| |
|
| | |
| | other_model->suffix.clear(); |
| | other_model->prefix.clear(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | bool mjCFrame::IsAncestor(const mjCFrame* child) const { |
| | if (!child) { |
| | return false; |
| | } |
| |
|
| | if (child == this) { |
| | return true; |
| | } |
| |
|
| | return IsAncestor(child->frame); |
| | } |
| |
|
| |
|
| |
|
| | void mjCFrame::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.childclass = &classname; |
| | spec.info = &info; |
| | } |
| |
|
| |
|
| |
|
| | void mjCFrame::CopyFromSpec() { |
| | *static_cast<mjsFrame*>(this) = spec; |
| | mjuu_copyvec(pos, spec.pos, 3); |
| | mjuu_copyvec(quat, spec.quat, 4); |
| | } |
| |
|
| |
|
| |
|
| | void mjCFrame::Compile() { |
| | if (compiled) { |
| | return; |
| | } |
| |
|
| | CopyFromSpec(); |
| | const char* err = ResolveOrientation(quat, compiler->degree, compiler->eulerseq, alt); |
| | if (err) { |
| | throw mjCError(this, "orientation specification error '%s' in site %d", err, id); |
| | } |
| |
|
| | |
| | if (frame) { |
| | frame->Compile(); |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, quat); |
| | } |
| |
|
| | mjuu_normvec(quat, 4); |
| | compiled = true; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCJoint::mjCJoint(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultJoint(&spec); |
| | elemtype = mjOBJ_JOINT; |
| |
|
| | |
| | spec_userdata_.clear(); |
| | body = 0; |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Joint(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| |
|
| | |
| | qposadr_ = -1; |
| | dofadr_ = -1; |
| | } |
| |
|
| |
|
| |
|
| | mjCJoint::mjCJoint(const mjCJoint& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCJoint& mjCJoint::operator=(const mjCJoint& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCJoint_*>(this) = static_cast<const mjCJoint_&>(other); |
| | *static_cast<mjsJoint*>(this) = static_cast<const mjsJoint&>(other); |
| | qposadr_ = -1; |
| | dofadr_ = -1; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | bool mjCJoint::is_limited() const { |
| | return islimited(limited, range); |
| | } |
| | bool mjCJoint::is_actfrclimited() const { |
| | return islimited(actfrclimited, actfrcrange); |
| | } |
| |
|
| |
|
| |
|
| | int mjCJoint::nq(mjtJoint joint_type) { |
| | switch (joint_type) { |
| | case mjJNT_FREE: |
| | return 7; |
| | case mjJNT_BALL: |
| | return 4; |
| | case mjJNT_SLIDE: |
| | case mjJNT_HINGE: |
| | return 1; |
| | } |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | int mjCJoint::nv(mjtJoint joint_type) { |
| | switch (joint_type) { |
| | case mjJNT_FREE: |
| | return 6; |
| | case mjJNT_BALL: |
| | return 3; |
| | case mjJNT_SLIDE: |
| | case mjJNT_HINGE: |
| | return 1; |
| | } |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | mjtNum* mjCJoint::qpos(const std::string& state_name) { |
| | if (qpos_.find(state_name) == qpos_.end()) { |
| | qpos_[state_name] = {mjNAN, 0, 0, 0, 0, 0, 0}; |
| | } |
| | return qpos_.at(state_name).data(); |
| | } |
| |
|
| |
|
| |
|
| | mjtNum* mjCJoint::qvel(const std::string& state_name) { |
| | if (qvel_.find(state_name) == qvel_.end()) { |
| | qvel_[state_name] = {mjNAN, 0, 0, 0, 0, 0}; |
| | } |
| | return qvel_.at(state_name).data(); |
| | } |
| |
|
| |
|
| |
|
| | void mjCJoint::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.userdata = &spec_userdata_; |
| | spec.info = &info; |
| | userdata = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCJoint::CopyFromSpec() { |
| | *static_cast<mjsJoint*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjCJoint::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_jnt) { |
| | throw mjCError(this, "user has more values than nuser_jnt in joint"); |
| | } |
| | userdata_.resize(model->nuser_jnt); |
| |
|
| | |
| | if (springdamper[0] || springdamper[1]) { |
| | if (springdamper[0] <= 0 || springdamper[1] <= 0) { |
| | throw mjCError(this, "when defined, springdamper values must be positive in joint"); |
| | } |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE) { |
| | limited = mjLIMITED_FALSE; |
| | } |
| |
|
| | |
| | else if (limited == mjLIMITED_AUTO) { |
| | bool hasrange = !(range[0] == 0 && range[1] == 0); |
| | checklimited(this, compiler->autolimits, "joint", "", limited, hasrange); |
| | } |
| |
|
| | |
| | if (is_limited()) { |
| | |
| | if (range[0] >= range[1] && type != mjJNT_BALL) { |
| | throw mjCError(this, "range[0] should be smaller than range[1] in joint"); |
| | } |
| | if (range[0] && type == mjJNT_BALL) { |
| | throw mjCError(this, "range[0] should be 0 in ball joint"); |
| | } |
| |
|
| | |
| | if (compiler->degree && (type == mjJNT_HINGE || type == mjJNT_BALL)) { |
| | if (range[0]) { |
| | range[0] *= mjPI/180.0; |
| | } |
| | if (range[1]) { |
| | range[1] *= mjPI/180.0; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE || type == mjJNT_BALL) { |
| | actfrclimited = mjLIMITED_FALSE; |
| | } |
| |
|
| | |
| | else if (actfrclimited == mjLIMITED_AUTO) { |
| | bool hasrange = !(actfrcrange[0] == 0 && actfrcrange[1] == 0); |
| | checklimited(this, compiler->autolimits, "joint", "", actfrclimited, hasrange); |
| | } |
| |
|
| | |
| | if (is_actfrclimited()) { |
| | |
| | if (actfrcrange[0] >= actfrcrange[1]) { |
| | throw mjCError(this, "actfrcrange[0] should be smaller than actfrcrange[1] in joint"); |
| | } |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE || type == mjJNT_BALL) { |
| | axis[0] = axis[1] = 0; |
| | axis[2] = 1; |
| | } |
| |
|
| | |
| | else if (frame) { |
| | mjuu_rotVecQuat(axis, axis, frame->quat); |
| | } |
| |
|
| | |
| | if (mjuu_normvec(axis, 3) < mjEPS) { |
| | throw mjCError(this, "axis too small in joint"); |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE && limited == mjLIMITED_TRUE) { |
| | throw mjCError(this, "limits should not be defined in free joint"); |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE) { |
| | mjuu_zerovec(pos, 3); |
| | } |
| |
|
| | |
| | else if (frame) { |
| | double qunit[4] = {1, 0, 0, 0}; |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, qunit); |
| | } |
| |
|
| | |
| | if (type == mjJNT_HINGE && compiler->degree) { |
| | ref *= mjPI/180.0; |
| | springref *= mjPI/180.0; |
| | } |
| |
|
| | |
| | if (type == mjJNT_FREE) { |
| | return 6; |
| | } else if (type == mjJNT_BALL) { |
| | return 3; |
| | } else { |
| | return 1; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCGeom::mjCGeom(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultGeom(&spec); |
| | elemtype = mjOBJ_GEOM; |
| |
|
| | mass_ = 0; |
| | body = 0; |
| | matid = -1; |
| | mesh = nullptr; |
| | hfield = nullptr; |
| | visual_ = false; |
| | mjuu_setvec(inertia, 0, 0, 0); |
| | inferinertia = true; |
| | spec_material_.clear(); |
| | spec_userdata_.clear(); |
| | spec_meshname_.clear(); |
| | spec_hfieldname_.clear(); |
| | spec_userdata_.clear(); |
| |
|
| | for (int i = 0; i < mjNFLUID; i++){ |
| | fluid[i] = 0; |
| | } |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Geom(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCGeom::mjCGeom(const mjCGeom& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCGeom& mjCGeom::operator=(const mjCGeom& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCGeom_*>(this) = static_cast<const mjCGeom_&>(other); |
| | *static_cast<mjsGeom*>(this) = static_cast<const mjsGeom&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCGeom::PointToLocal(void) { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.info = &info; |
| | spec.userdata = &spec_userdata_; |
| | spec.material = &spec_material_; |
| | spec.meshname = &spec_meshname_; |
| | spec.hfieldname = &spec_hfieldname_; |
| | spec.plugin.plugin_name = &plugin_name; |
| | spec.plugin.name = &plugin_instance_name; |
| | userdata = nullptr; |
| | hfieldname = nullptr; |
| | meshname = nullptr; |
| | material = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCGeom::CopyFromSpec() { |
| | *static_cast<mjsGeom*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | hfieldname_ = spec_hfieldname_; |
| | meshname_ = spec_meshname_; |
| | material_ = spec_material_; |
| | plugin.active = spec.plugin.active; |
| | plugin.element = spec.plugin.element; |
| | plugin.plugin_name = spec.plugin.plugin_name; |
| | plugin.name = spec.plugin.name; |
| | } |
| |
|
| |
|
| |
|
| | void mjCGeom::CopyPlugin() { |
| | model->CopyExplicitPlugin(this); |
| | } |
| |
|
| |
|
| |
|
| | void mjCGeom::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!spec_material_.empty() && model != m) { |
| | spec_material_ = m->prefix + spec_material_ + m->suffix; |
| | } |
| | if (!spec_hfieldname_.empty() && model != m) { |
| | spec_hfieldname_ = m->prefix + spec_hfieldname_ + m->suffix; |
| | } |
| | if (!spec_meshname_.empty() && model != m) { |
| | spec_meshname_ = m->prefix + spec_meshname_ + m->suffix; |
| | } |
| | if (!plugin_instance_name.empty()) { |
| | plugin_instance_name = m->prefix + plugin_instance_name + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | double mjCGeom::GetVolume() const { |
| | |
| | if (type == mjGEOM_MESH || type == mjGEOM_SDF) { |
| | if (mesh->id < 0 || !((std::size_t) mesh->id <= model->Meshes().size())) { |
| | throw mjCError(this, "invalid mesh id in mesh geom"); |
| | } |
| |
|
| | return mesh->GetVolumeRef(); |
| | } |
| |
|
| | |
| | switch (type) { |
| | case mjGEOM_SPHERE: { |
| | double radius = size[0]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | return 4 * mjPI * radius * radius * radius / 3; |
| | case mjINERTIA_SHELL: |
| | return 4 * mjPI * radius * radius; |
| | } |
| | break; |
| | } |
| | case mjGEOM_CAPSULE: { |
| | double height = 2 * size[1]; |
| | double radius = size[0]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | return mjPI * (radius * radius * height + 4 * radius * radius * radius / 3); |
| | case mjINERTIA_SHELL: |
| | return 4 * mjPI * radius * radius + 2 * mjPI * radius * height; |
| | } |
| | break; |
| | } |
| | case mjGEOM_CYLINDER: { |
| | double height = 2 * size[1]; |
| | double radius = size[0]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | return mjPI * radius * radius * height; |
| | case mjINERTIA_SHELL: |
| | return 2 * mjPI * radius * radius + 2 * mjPI * radius * height; |
| | } |
| | break; |
| | } |
| | case mjGEOM_ELLIPSOID: { |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | return 4 * mjPI * size[0] * size[1] * size[2] / 3; |
| | case mjINERTIA_SHELL: { |
| | |
| | |
| | double p = 1.6075; |
| | double tmp = std::pow(size[0] * size[1], p) + |
| | std::pow(size[1] * size[2], p) + |
| | std::pow(size[2] * size[0], p); |
| | return 4 * mjPI * std::pow(tmp / 3, 1 / p); |
| | } |
| | } |
| | break; |
| | } |
| | case mjGEOM_HFIELD: |
| | case mjGEOM_BOX: { |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | return size[0] * size[1] * size[2] * 8; |
| | case mjINERTIA_SHELL: |
| | return 8 * (size[0] * size[1] + size[1] * size[2] + size[2] * size[0]); |
| | } |
| | break; |
| | } |
| | default: |
| | break; |
| | } |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCGeom::SetInertia(void) { |
| | |
| | if (type == mjGEOM_MESH || type == mjGEOM_SDF) { |
| | if (mesh->id < 0 || !((std::size_t)mesh->id <= model->Meshes().size())) { |
| | throw mjCError(this, "invalid mesh id in mesh geom"); |
| | } |
| |
|
| | double* boxsz = mesh->GetInertiaBoxPtr(); |
| | inertia[0] = mass_ * (boxsz[1] * boxsz[1] + boxsz[2] * boxsz[2]) / 3; |
| | inertia[1] = mass_ * (boxsz[0] * boxsz[0] + boxsz[2] * boxsz[2]) / 3; |
| | inertia[2] = mass_ * (boxsz[0] * boxsz[0] + boxsz[1] * boxsz[1]) / 3; |
| |
|
| | return; |
| | } |
| |
|
| | |
| | switch (type) { |
| | case mjGEOM_SPHERE: { |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| | inertia[0] = inertia[1] = inertia[2] = 2 * mass_ * size[0] * size[0] / 5; |
| | return; |
| | case mjINERTIA_SHELL: |
| | inertia[0] = inertia[1] = inertia[2] = 2 * mass_ * size[0] * size[0] / 3; |
| | return; |
| | } |
| | break; |
| | } |
| | case mjGEOM_CAPSULE: { |
| | double halfheight = size[1]; |
| | double height = 2 * size[1]; |
| | double radius = size[0]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: { |
| | double sphere_mass = |
| | mass_ * 4 * radius / (4 * radius + 3 * height); |
| | double cylinder_mass = mass_ - sphere_mass; |
| |
|
| | |
| | inertia[0] = inertia[1] = cylinder_mass * (3 * radius * radius + height * height) / 12; |
| | inertia[2] = cylinder_mass * radius * radius / 2; |
| |
|
| | |
| | double sphere_inertia = 2 * sphere_mass * radius * radius / 5; |
| | inertia[0] += sphere_inertia + sphere_mass * height * (3 * radius + 2 * height) / 8; |
| | inertia[1] += sphere_inertia + sphere_mass * height * (3 * radius + 2 * height) / 8; |
| | inertia[2] += sphere_inertia; |
| | return; |
| | } |
| | case mjINERTIA_SHELL: { |
| | |
| | double Asphere = 4 * mjPI * radius * radius; |
| | double Acylinder = 2 * mjPI * radius * height; |
| | double Atotal = Asphere + Acylinder; |
| |
|
| | |
| | double sphere_mass = mass_ * Asphere / Atotal; |
| | double cylinder_mass = mass_ - sphere_mass; |
| |
|
| | |
| | inertia[0] = inertia[1] = cylinder_mass * (6 * radius * radius + height * height) / 12; |
| | inertia[2] = cylinder_mass * radius * radius; |
| |
|
| | |
| | double sphere_inertia = 2 * sphere_mass * radius * radius / 3; |
| | double hs_com = radius / 2; |
| | double hs_pos = halfheight + hs_com; |
| | inertia[0] += sphere_inertia + sphere_mass * (hs_pos * hs_pos - hs_com * hs_com); |
| | inertia[1] += sphere_inertia + sphere_mass * (hs_pos * hs_pos - hs_com * hs_com); |
| | inertia[2] += sphere_inertia; |
| | return; |
| | } |
| | break; |
| | } |
| | break; |
| | } |
| | case mjGEOM_CYLINDER: { |
| | double halfheight = size[1]; |
| | double height = 2 * halfheight; |
| | double radius = size[0]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: |
| |
|
| | inertia[0] = inertia[1] = mass_ * (3 * radius * radius + height * height) / 12; |
| | inertia[2] = mass_ * radius * radius / 2; |
| | return; |
| | case mjINERTIA_SHELL: { |
| | |
| | double Adisk = mjPI * radius * radius; |
| | double Acylinder = 2 * mjPI * radius * height; |
| | double Atotal = 2 * Adisk + Acylinder; |
| |
|
| | |
| | double mass_disk = mass_ * Adisk / Atotal; |
| | double mass_cylinder = mass_ - 2 * mass_disk; |
| |
|
| | |
| | inertia[0] = inertia[1] = mass_cylinder * (6 * radius * radius + height * height) / 12; |
| | inertia[2] = mass_cylinder * radius * radius; |
| |
|
| | |
| | double inertia_disk_x = mass_disk * radius * radius / 4 + |
| | mass_disk * halfheight * halfheight; |
| | double inertia_disk_z = mass_disk * radius * radius / 2; |
| |
|
| | |
| | inertia[0] += 2 * inertia_disk_x; |
| | inertia[1] += 2 * inertia_disk_x; |
| | inertia[2] += 2 * inertia_disk_z; |
| | return; |
| | } |
| | } |
| | break; |
| | } |
| | case mjGEOM_ELLIPSOID: { |
| | double s00 = size[0] * size[0]; |
| | double s11 = size[1] * size[1]; |
| | double s22 = size[2] * size[2]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: { |
| | inertia[0] = mass_ * (s11 + s22) / 5; |
| | inertia[1] = mass_ * (s00 + s22) / 5; |
| | inertia[2] = mass_ * (s00 + s11) / 5; |
| | return; |
| | } |
| | case mjINERTIA_SHELL: { |
| | |
| | double eps = 1e-6; |
| |
|
| | |
| | double Va = 4 * mjPI * size[0] * size[1] * size[2] / 3; |
| |
|
| | |
| | double ae = size[0] + eps; |
| | double be = size[1] + eps; |
| | double ce = size[2] + eps; |
| | double Vb = 4 * mjPI * ae * be * ce / 3; |
| |
|
| | |
| | double density = mass_ / (Vb - Va); |
| |
|
| | |
| | double mass_a = Va * density; |
| | double inertia_a[3]; |
| | inertia_a[0] = mass_a * (s11 + s22) / 5; |
| | inertia_a[1] = mass_a * (s00 + s22) / 5; |
| | inertia_a[2] = mass_a * (s00 + s11) / 5; |
| |
|
| | double mass_b = Vb * density; |
| | double inertia_b[3]; |
| | inertia_b[0] = mass_b * (be * be + ce * ce) / 5; |
| | inertia_b[1] = mass_b * (ae * ae + ce * ce) / 5; |
| | inertia_b[2] = mass_b * (ae * ae + be * be) / 5; |
| |
|
| | |
| | inertia[0] = inertia_b[0] - inertia_a[0]; |
| | inertia[1] = inertia_b[1] - inertia_a[1]; |
| | inertia[2] = inertia_b[2] - inertia_a[2]; |
| | return; |
| | } |
| | } |
| | break; |
| | } |
| | case mjGEOM_HFIELD: |
| | case mjGEOM_BOX: { |
| | double s00 = size[0] * size[0]; |
| | double s11 = size[1] * size[1]; |
| | double s22 = size[2] * size[2]; |
| | switch (typeinertia) { |
| | case mjINERTIA_VOLUME: { |
| | inertia[0] = mass_ * (s11 + s22) / 3; |
| | inertia[1] = mass_ * (s00 + s22) / 3; |
| | inertia[2] = mass_ * (s00 + s11) / 3; |
| | return; |
| | } |
| | case mjINERTIA_SHELL: { |
| | |
| | double lx = 2 * size[0]; |
| | double ly = 2 * size[1]; |
| | double lz = 2 * size[2]; |
| |
|
| | |
| | double A0 = lx * ly; |
| | double A1 = ly * lz; |
| | double A2 = lz * lx; |
| | double Atotal = 2 * (A0 + A1 + A2); |
| |
|
| | |
| | double mass0 = mass_ * A0 / Atotal; |
| | double Ix0 = mass0 * ly * ly / 12; |
| | double Iy0 = mass0 * lx * lx / 12; |
| | double Iz0 = mass0 * (lx * lx + ly * ly) / 12; |
| |
|
| | |
| | double mass1 = mass_ * A1 / Atotal; |
| | double Ix1 = mass1 * (ly * ly + lz * lz) / 12; |
| | double Iy1 = mass1 * lz * lz / 12; |
| | double Iz1 = mass1 * ly * ly / 12; |
| |
|
| | |
| | double mass2 = mass_ * A2 / Atotal; |
| | double Ix2 = mass2 * lz * lz / 12; |
| | double Iy2 = mass2 * (lx * lx + lz * lz) / 12; |
| | double Iz2 = mass2 * lx * lx / 12; |
| |
|
| | |
| | inertia[0] = 2 * (mass0 * s22 + mass2 * s11 + Ix0 + Ix1 + Ix2); |
| | inertia[1] = 2 * (mass0 * s22 + mass1 * s00 + Iy0 + Iy1 + Iy2); |
| | inertia[2] = 2 * (mass1 * s00 + mass2 * s11 + Iz0 + Iz1 + Iz2); |
| | return; |
| | } |
| | break; |
| | } |
| | break; |
| | } |
| | default: |
| | inertia[0] = inertia[1] = inertia[2] = 0; |
| | return; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | double mjCGeom::GetRBound(void) { |
| | const double *aamm, *hsize; |
| | double haabb[3] = {0}; |
| |
|
| | switch (type) { |
| | case mjGEOM_HFIELD: |
| | hsize = hfield->size; |
| | return sqrt(hsize[0]*hsize[0] + hsize[1]*hsize[1] + |
| | std::max(hsize[2]*hsize[2], hsize[3]*hsize[3])); |
| |
|
| | case mjGEOM_SPHERE: |
| | return size[0]; |
| |
|
| | case mjGEOM_CAPSULE: |
| | return size[0]+size[1]; |
| |
|
| | case mjGEOM_CYLINDER: |
| | return sqrt(size[0]*size[0]+size[1]*size[1]); |
| |
|
| | case mjGEOM_ELLIPSOID: |
| | return std::max(std::max(size[0], size[1]), size[2]); |
| |
|
| | case mjGEOM_BOX: |
| | return sqrt(size[0]*size[0]+size[1]*size[1]+size[2]*size[2]); |
| |
|
| | case mjGEOM_MESH: |
| | case mjGEOM_SDF: |
| | aamm = mesh->aamm(); |
| | haabb[0] = std::max(std::abs(aamm[0]), std::abs(aamm[3])); |
| | haabb[1] = std::max(std::abs(aamm[1]), std::abs(aamm[4])); |
| | haabb[2] = std::max(std::abs(aamm[2]), std::abs(aamm[5])); |
| | return sqrt(haabb[0]*haabb[0] + haabb[1]*haabb[1] + haabb[2]*haabb[2]); |
| |
|
| | default: |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | double mjCGeom::GetAddedMassKappa(double dx, double dy, double dz) { |
| | |
| | |
| | |
| |
|
| | |
| | |
| | |
| | |
| | |
| | static constexpr double kronrod_w[15] = { |
| | 0.01146766, 0.03154605, 0.05239501, 0.07032663, 0.08450236, |
| | 0.09517529, 0.10221647, 0.10474107, 0.10221647, 0.09517529, |
| | 0.08450236, 0.07032663, 0.05239501, 0.03154605, 0.01146766}; |
| | |
| | |
| | static constexpr double kronrod_l[15] = { |
| | 7.865151709349917e-08, 1.7347976913907274e-05, 0.0003548008144506193, |
| | 0.002846636252924549, 0.014094260903596077, 0.053063261727396636, |
| | 0.17041978741317773, 0.5, 1.4036301548686991, 3.9353484827022642, |
| | 11.644841677041734, 39.53187807410903, 177.5711362220801, |
| | 1429.4772912937397, 54087.416549217705}; |
| | |
| | static constexpr double kronrod_d[15] = { |
| | 5.538677720489877e-05, 0.002080868285293228, 0.016514126520723166, |
| | 0.07261900344370877, 0.23985243401862602, 0.6868318249020725, |
| | 1.8551129519182894, 5.0, 14.060031152313941, 43.28941239611009, |
| | 156.58546376397112, 747.9826085305024, 5827.4042950027115, |
| | 116754.0197944512, 25482945.327264845}; |
| |
|
| | const double invdx2 = 1.0 / (dx * dx); |
| | const double invdy2 = 1.0 / (dy * dy); |
| | const double invdz2 = 1.0 / (dz * dz); |
| |
|
| | |
| | |
| | const double scale = std::pow(dx*dx*dx * dy * dz, 0.4); |
| | double kappa = 0.0; |
| | for (int i = 0; i < 15; ++i) { |
| | const double lambda = scale * kronrod_l[i]; |
| | const double denom = (1 + lambda*invdx2) * std::sqrt( |
| | (1 + lambda*invdx2) * (1 + lambda*invdy2) * (1 + lambda*invdz2)); |
| | kappa += scale * kronrod_d[i] / denom * kronrod_w[i]; |
| | } |
| | return kappa * invdx2; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCGeom::SetFluidCoefs(void) { |
| | double dx, dy, dz; |
| |
|
| | |
| | switch (type) { |
| | case mjGEOM_SPHERE: |
| | dx = size[0]; |
| | dy = size[0]; |
| | dz = size[0]; |
| | break; |
| |
|
| | case mjGEOM_CAPSULE: |
| | dx = size[0]; |
| | dy = size[0]; |
| | dz = size[1] + size[0]; |
| | break; |
| |
|
| | case mjGEOM_CYLINDER: |
| | dx = size[0]; |
| | dy = size[0]; |
| | dz = size[1]; |
| | break; |
| |
|
| | default: |
| | dx = size[0]; |
| | dy = size[1]; |
| | dz = size[2]; |
| | } |
| |
|
| | |
| | const double volume = 4.0 / 3.0 * mjPI * dx * dy * dz; |
| |
|
| | |
| | const double kx = GetAddedMassKappa(dx, dy, dz); |
| | const double ky = GetAddedMassKappa(dy, dz, dx); |
| | const double kz = GetAddedMassKappa(dz, dx, dy); |
| |
|
| | |
| | |
| | const auto pow2 = [](const double val) { return val * val; }; |
| | const double Ixfac = pow2(dy*dy - dz*dz) * std::abs(kz - ky) / std::max( |
| | mjEPS, std::abs(2*(dy*dy - dz*dz) + (dy*dy + dz*dz)*(ky - kz))); |
| | const double Iyfac = pow2(dz*dz - dx*dx) * std::abs(kx - kz) / std::max( |
| | mjEPS, std::abs(2*(dz*dz - dx*dx) + (dz*dz + dx*dx)*(kz - kx))); |
| | const double Izfac = pow2(dx*dx - dy*dy) * std::abs(ky - kx) / std::max( |
| | mjEPS, std::abs(2*(dx*dx - dy*dy) + (dx*dx + dy*dy)*(kx - ky))); |
| |
|
| | mjtNum virtual_mass[3]; |
| | virtual_mass[0] = volume * kx / std::max(mjEPS, 2-kx); |
| | virtual_mass[1] = volume * ky / std::max(mjEPS, 2-ky); |
| | virtual_mass[2] = volume * kz / std::max(mjEPS, 2-kz); |
| | mjtNum virtual_inertia[3]; |
| | virtual_inertia[0] = volume*Ixfac/5; |
| | virtual_inertia[1] = volume*Iyfac/5; |
| | virtual_inertia[2] = volume*Izfac/5; |
| |
|
| | writeFluidGeomInteraction(fluid, &fluid_ellipsoid, &fluid_coefs[0], |
| | &fluid_coefs[1], &fluid_coefs[2], |
| | &fluid_coefs[3], &fluid_coefs[4], |
| | virtual_mass, virtual_inertia); |
| | } |
| |
|
| |
|
| | |
| | void mjCGeom::ComputeAABB(void) { |
| | double aamm[6]; |
| | switch (type) { |
| | case mjGEOM_HFIELD: |
| | aamm[0] = -hfield->size[0]; |
| | aamm[1] = -hfield->size[1]; |
| | aamm[2] = -hfield->size[3]; |
| | aamm[3] = hfield->size[0]; |
| | aamm[4] = hfield->size[1]; |
| | aamm[5] = hfield->size[2]; |
| | break; |
| |
|
| | case mjGEOM_SPHERE: |
| | aamm[3] = aamm[4] = aamm[5] = size[0]; |
| | mjuu_setvec(aamm, -aamm[3], -aamm[4], -aamm[5]); |
| | break; |
| |
|
| | case mjGEOM_CAPSULE: |
| | aamm[3] = aamm[4] = size[0]; |
| | aamm[5] = size[0] + size[1]; |
| | mjuu_setvec(aamm, -aamm[3], -aamm[4], -aamm[5]); |
| | break; |
| |
|
| | case mjGEOM_CYLINDER: |
| | aamm[3] = aamm[4] = size[0]; |
| | aamm[5] = size[1]; |
| | mjuu_setvec(aamm, -aamm[3], -aamm[4], -aamm[5]); |
| | break; |
| |
|
| | case mjGEOM_MESH: |
| | case mjGEOM_SDF: |
| | mjuu_copyvec(aamm, mesh->aamm(), 6); |
| | break; |
| |
|
| | case mjGEOM_PLANE: |
| | aamm[0] = aamm[1] = aamm[2] = -mjMAXVAL; |
| | aamm[3] = aamm[4] = mjMAXVAL; |
| | aamm[5] = 0; |
| | break; |
| |
|
| | default: |
| | mjuu_copyvec(aamm+3, size, 3); |
| | mjuu_setvec(aamm, -size[0], -size[1], -size[2]); |
| | break; |
| | } |
| |
|
| | |
| | double pos[] = {(aamm[3] + aamm[0]) / 2, (aamm[4] + aamm[1]) / 2, |
| | (aamm[5] + aamm[2]) / 2}; |
| | double size[] = {(aamm[3] - aamm[0]) / 2, (aamm[4] - aamm[1]) / 2, |
| | (aamm[5] - aamm[2]) / 2}; |
| | mjuu_copyvec(aabb, pos, 3); |
| | mjuu_copyvec(aabb+3, size, 3); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCGeom::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_geom) { |
| | throw mjCError(this, "user has more values than nuser_geom in geom '%s' (id = %d)", |
| | name.c_str(), id); |
| | } |
| | userdata_.resize(model->nuser_geom); |
| |
|
| | |
| | if (type < 0 || type >= mjNGEOMTYPES) { |
| | throw mjCError(this, "invalid type in geom"); |
| | } |
| |
|
| | |
| | if (condim != 1 && condim != 3 && condim != 4 && condim != 6) { |
| | throw mjCError(this, "invalid condim in geom"); |
| | } |
| |
|
| | |
| | if ((type == mjGEOM_MESH || type == mjGEOM_SDF) && !mesh) { |
| | throw mjCError(this, "mesh geom '%s' (id = %d) must have valid meshid", name.c_str(), id); |
| | } |
| |
|
| | |
| | if ((type == mjGEOM_HFIELD && !hfield) || (type != mjGEOM_HFIELD && hfield)) { |
| | throw mjCError(this, "hfield geom '%s' (id = %d) must have valid hfieldid", name.c_str(), id); |
| | } |
| |
|
| | |
| | if (type == mjGEOM_PLANE && body->weldid != 0) { |
| | throw mjCError(this, "plane only allowed in static bodies"); |
| | } |
| |
|
| | |
| | visual_ = !contype && !conaffinity; |
| |
|
| | |
| | mjuu_normvec(quat, 4); |
| |
|
| | |
| | if (mjuu_defined(fromto[0])) { |
| | |
| | if (type != mjGEOM_CAPSULE && |
| | type != mjGEOM_CYLINDER && |
| | type != mjGEOM_ELLIPSOID && |
| | type != mjGEOM_BOX) { |
| | throw mjCError(this, "fromto requires capsule, cylinder, box or ellipsoid in geom"); |
| | } |
| |
|
| | |
| | if (pos[0] || pos[1] || pos[2]) { |
| | throw mjCError(this, "both pos and fromto defined in geom"); |
| | } |
| |
|
| | |
| | double vec[3] = { |
| | fromto[0]-fromto[3], |
| | fromto[1]-fromto[4], |
| | fromto[2]-fromto[5] |
| | }; |
| | size[1] = mjuu_normvec(vec, 3)/2; |
| | if (size[1] < mjEPS) { |
| | throw mjCError(this, "fromto points too close in geom"); |
| | } |
| |
|
| | |
| | if (type == mjGEOM_ELLIPSOID || type == mjGEOM_BOX) { |
| | size[2] = size[1]; |
| | size[1] = size[0]; |
| | } |
| |
|
| | |
| | pos[0] = (fromto[0]+fromto[3])/2; |
| | pos[1] = (fromto[1]+fromto[4])/2; |
| | pos[2] = (fromto[2]+fromto[5])/2; |
| |
|
| | |
| | mjuu_z2quat(quat, vec); |
| | } |
| |
|
| | |
| | else { |
| | const char* err = ResolveOrientation(quat, compiler->degree, compiler->eulerseq, alt); |
| | if (err) { |
| | throw mjCError(this, "orientation specification error '%s' in geom %d", err, id); |
| | } |
| | } |
| |
|
| | |
| | if (mesh) { |
| | |
| | if (mjuu_defined(fromto[0])) { |
| | throw mjCError(this, "fromto cannot be used with mesh geom"); |
| | } |
| |
|
| | |
| | mjCMesh* pmesh = mesh; |
| |
|
| | |
| | if (type != mjGEOM_MESH && type != mjGEOM_SDF) { |
| | double meshpos[3]; |
| | mesh->FitGeom(this, meshpos); |
| |
|
| | |
| | meshname_.clear(); |
| | mesh = nullptr; |
| | mjuu_copyvec(pmesh->GetPosPtr(), meshpos, 3); |
| | } else if (typeinertia == mjINERTIA_SHELL) { |
| | throw mjCError(this, "for mesh geoms, inertia should be specified in the mesh asset"); |
| | } |
| |
|
| | |
| | mjuu_frameaccum(pos, quat, pmesh->GetPosPtr(), pmesh->GetQuatPtr()); |
| | } |
| |
|
| | |
| | checksize(size, type, this, name.c_str(), id); |
| |
|
| | |
| | if (type == mjGEOM_HFIELD) { |
| | size[0] = hfield->size[0]; |
| | size[1] = hfield->size[1]; |
| | size[2] = 0.25 * hfield->size[2] + 0.5 * hfield->size[3]; |
| | } else if (type == mjGEOM_MESH || type == mjGEOM_SDF) { |
| | const double* aamm = mesh->aamm(); |
| | size[0] = std::max(std::abs(aamm[0]), std::abs(aamm[3])); |
| | size[1] = std::max(std::abs(aamm[1]), std::abs(aamm[4])); |
| | size[2] = std::max(std::abs(aamm[2]), std::abs(aamm[5])); |
| | } |
| |
|
| | for (double s : size) { |
| | if (std::isnan(s)) { |
| | throw mjCError(this, "nan size in geom"); |
| | } |
| | } |
| | |
| | ComputeAABB(); |
| |
|
| | |
| | if (inferinertia) { |
| | |
| | if (mjuu_defined(mass)) { |
| | if (mass == 0) { |
| | mass_ = 0; |
| | density = 0; |
| | } else if (GetVolume() > mjEPS) { |
| | mass_ = mass; |
| | density = mass / GetVolume(); |
| | SetInertia(); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | if (density == 0) { |
| | mass_ = 0; |
| | } else { |
| | mass_ = density * GetVolume(); |
| | SetInertia(); |
| | } |
| | } |
| |
|
| |
|
| | |
| | if (mass_ < 0 || inertia[0] < 0 || inertia[1] < 0 || inertia[2] < 0 || density < 0) |
| | throw mjCError(this, "mass, inertia or density are negative in geom"); |
| | } |
| |
|
| | |
| | if (fluid_ellipsoid > 0) { |
| | SetFluidCoefs(); |
| | } |
| |
|
| | |
| | if (plugin.active) { |
| | if (plugin_name.empty() && plugin_instance_name.empty()) { |
| | throw mjCError( |
| | this, "neither 'plugin' nor 'instance' is specified for geom"); |
| | } |
| |
|
| | mjCPlugin* plugin_instance = static_cast<mjCPlugin*>(plugin.element); |
| | model->ResolvePlugin(this, plugin_name, plugin_instance_name, &plugin_instance); |
| | plugin.element = plugin_instance; |
| | const mjpPlugin* pplugin = mjp_getPluginAtSlot(plugin_instance->plugin_slot); |
| | if (!(pplugin->capabilityflags & mjPLUGIN_SDF)) { |
| | throw mjCError(this, "plugin '%s' does not support sign distance fields", pplugin->name); |
| | } |
| | } |
| |
|
| | |
| | if (frame) { |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, quat); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCSite::mjCSite(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultSite(&spec); |
| | elemtype = mjOBJ_SITE; |
| |
|
| | |
| | body = 0; |
| | matid = -1; |
| | spec_material_.clear(); |
| | spec_userdata_.clear(); |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Site(); |
| | } |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| | } |
| |
|
| |
|
| |
|
| | mjCSite::mjCSite(const mjCSite& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCSite& mjCSite::operator=(const mjCSite& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCSite_*>(this) = static_cast<const mjCSite_&>(other); |
| | *static_cast<mjsSite*>(this) = static_cast<const mjsSite&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSite::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.info = &info; |
| | spec.material = &spec_material_; |
| | spec.userdata = &spec_userdata_; |
| | userdata = nullptr; |
| | material = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSite::CopyFromSpec() { |
| | *static_cast<mjsSite*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | material_ = spec_material_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSite::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!spec_material_.empty() && model != m) { |
| | spec_material_ = m->prefix + spec_material_ + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCSite::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_site) { |
| | throw mjCError(this, "user has more values than nuser_site in site"); |
| | } |
| | userdata_.resize(model->nuser_site); |
| |
|
| | |
| | if (type < 0 || type >= mjNGEOMTYPES) { |
| | throw mjCError(this, "invalid type in site"); |
| | } |
| |
|
| | |
| | if (type == mjGEOM_MESH || type == mjGEOM_HFIELD || type == mjGEOM_PLANE) { |
| | throw mjCError(this, "meshes, hfields and planes not allowed in site"); |
| | } |
| |
|
| | |
| | if (mjuu_defined(fromto[0])) { |
| | |
| | if (type != mjGEOM_CAPSULE && |
| | type != mjGEOM_CYLINDER && |
| | type != mjGEOM_ELLIPSOID && |
| | type != mjGEOM_BOX) { |
| | throw mjCError(this, "fromto requires capsule, cylinder, box or ellipsoid in geom"); |
| | } |
| |
|
| | |
| | if (pos[0] || pos[1] || pos[2]) { |
| | throw mjCError(this, "both pos and fromto defined in geom"); |
| | } |
| |
|
| | |
| | double vec[3] = {fromto[0]-fromto[3], fromto[1]-fromto[4], fromto[2]-fromto[5]}; |
| | size[1] = mjuu_normvec(vec, 3)/2; |
| | if (size[1] < mjEPS) { |
| | throw mjCError(this, "fromto points too close in geom"); |
| | } |
| |
|
| | |
| | if (type == mjGEOM_ELLIPSOID || type == mjGEOM_BOX) { |
| | size[2] = size[1]; |
| | size[1] = size[0]; |
| | } |
| |
|
| | |
| | pos[0] = (fromto[0]+fromto[3])/2; |
| | pos[1] = (fromto[1]+fromto[4])/2; |
| | pos[2] = (fromto[2]+fromto[5])/2; |
| |
|
| | |
| | mjuu_z2quat(quat, vec); |
| | } |
| |
|
| | |
| | else { |
| | const char* err = ResolveOrientation(quat, compiler->degree, compiler->eulerseq, alt); |
| | if (err) { |
| | throw mjCError(this, "orientation specification error '%s' in site %d", err, id); |
| | } |
| | } |
| |
|
| | |
| | if (frame) { |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, quat); |
| | } |
| |
|
| | |
| | mjuu_normvec(quat, 4); |
| |
|
| | |
| | checksize(size, type, this, name.c_str(), id); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCCamera::mjCCamera(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultCamera(&spec); |
| | elemtype = mjOBJ_CAMERA; |
| |
|
| | |
| | body = 0; |
| | targetbodyid = -1; |
| | spec_targetbody_.clear(); |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Camera(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCCamera::mjCCamera(const mjCCamera& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCCamera& mjCCamera::operator=(const mjCCamera& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCCamera_*>(this) = static_cast<const mjCCamera_&>(other); |
| | *static_cast<mjsCamera*>(this) = static_cast<const mjsCamera&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCCamera::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.userdata = &spec_userdata_; |
| | spec.targetbody = &spec_targetbody_; |
| | spec.info = &info; |
| | userdata = nullptr; |
| | targetbody = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCCamera::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!spec_targetbody_.empty()) { |
| | spec_targetbody_ = m->prefix + spec_targetbody_ + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCCamera::CopyFromSpec() { |
| | *static_cast<mjsCamera*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | targetbody_ = spec_targetbody_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCCamera::ResolveReferences(const mjCModel* m) { |
| | if (!targetbody_.empty()) { |
| | mjCBody* tb = (mjCBody*)m->FindObject(mjOBJ_BODY, targetbody_); |
| | if (tb) { |
| | targetbodyid = tb->id; |
| | } else { |
| | throw mjCError(this, "unknown target body in camera"); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCCamera::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_cam) { |
| | throw mjCError(this, "user has more values than nuser_cam in camera"); |
| | } |
| | userdata_.resize(model->nuser_cam); |
| |
|
| | |
| | const char* err = ResolveOrientation(quat, compiler->degree, compiler->eulerseq, alt); |
| | if (err) { |
| | throw mjCError(this, "orientation specification error '%s' in camera %d", err, id); |
| | } |
| |
|
| | |
| | if (frame) { |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, quat); |
| | } |
| |
|
| | |
| | mjuu_normvec(quat, 4); |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | if (fovy >= 180) { |
| | throw mjCError(this, "fovy too large in camera '%s' (id = %d, value = %d)", |
| | name.c_str(), id, fovy); |
| | } |
| |
|
| | |
| | if ((principal_length[0] && principal_pixel[0]) || |
| | (principal_length[1] && principal_pixel[1])) { |
| | throw mjCError(this, "principal length duplicated in camera"); |
| | } |
| |
|
| | if ((focal_length[0] && focal_pixel[0]) || |
| | (focal_length[1] && focal_pixel[1])) { |
| | throw mjCError(this, "focal length duplicated in camera"); |
| | } |
| |
|
| | |
| | if (sensor_size[0] > 0 && sensor_size[1] > 0) { |
| | float pixel_density[2] = { |
| | (float)resolution[0] / sensor_size[0], |
| | (float)resolution[1] / sensor_size[1], |
| | }; |
| |
|
| | |
| | intrinsic[0] = focal_pixel[0] / pixel_density[0] + focal_length[0]; |
| | intrinsic[1] = focal_pixel[1] / pixel_density[1] + focal_length[1]; |
| | intrinsic[2] = principal_pixel[0] / pixel_density[0] + principal_length[0]; |
| | intrinsic[3] = principal_pixel[1] / pixel_density[1] + principal_length[1]; |
| |
|
| | |
| | fovy = std::atan2(sensor_size[1]/2, intrinsic[1]) * 360.0 / mjPI; |
| | } else { |
| | intrinsic[0] = model->visual.map.znear; |
| | intrinsic[1] = model->visual.map.znear; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCLight::mjCLight(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultLight(&spec); |
| | elemtype = mjOBJ_LIGHT; |
| |
|
| | |
| | body = 0; |
| | targetbodyid = -1; |
| | texid = -1; |
| | spec_targetbody_.clear(); |
| | spec_texture_.clear(); |
| |
|
| |
|
| | |
| | if (_def) { |
| | *this = _def->Light(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | PointToLocal(); |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCLight::mjCLight(const mjCLight& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCLight& mjCLight::operator=(const mjCLight& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCLight_*>(this) = static_cast<const mjCLight_&>(other); |
| | *static_cast<mjsLight*>(this) = static_cast<const mjsLight&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCLight::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.targetbody = &spec_targetbody_; |
| | spec.texture = &spec_texture_; |
| | spec.info = &info; |
| | targetbody = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCLight::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!spec_targetbody_.empty()) { |
| | spec_targetbody_ = m->prefix + spec_targetbody_ + m->suffix; |
| | } |
| | if (!spec_texture_.empty()) { |
| | spec_texture_ = m->prefix + spec_texture_ + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCLight::CopyFromSpec() { |
| | *static_cast<mjsLight*>(this) = spec; |
| | targetbody_ = spec_targetbody_; |
| | texture_ = spec_texture_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCLight::ResolveReferences(const mjCModel* m) { |
| | if (!targetbody_.empty()) { |
| | mjCBody* tb = (mjCBody*)m->FindObject(mjOBJ_BODY, targetbody_); |
| | if (tb) { |
| | targetbodyid = tb->id; |
| | } else { |
| | throw mjCError(this, "unknown target body in light"); |
| | } |
| | } |
| | if (!texture_.empty()) { |
| | mjCTexture* tex = (mjCTexture*)m->FindObject(mjOBJ_TEXTURE, texture_); |
| | if (tex) { |
| | texid = tex->id; |
| | } else { |
| | throw mjCError(this, "unknown texture in light"); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCLight::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (frame) { |
| | |
| | double qunit[4]= {1, 0, 0, 0}; |
| | mjuu_frameaccumChild(frame->pos, frame->quat, pos, qunit); |
| |
|
| | |
| | mjuu_rotVecQuat(dir, dir, frame->quat); |
| | } |
| |
|
| | |
| | if (mjuu_normvec(dir, 3) < mjEPS) { |
| | throw mjCError(this, "zero direction in light"); |
| | } |
| |
|
| | |
| | ResolveReferences(model); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCHField::mjCHField(mjCModel* _model) { |
| | mjs_defaultHField(&spec); |
| | elemtype = mjOBJ_HFIELD; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | data.clear(); |
| | spec_file_.clear(); |
| | spec_userdata_.clear(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCHField::mjCHField(const mjCHField& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCHField& mjCHField::operator=(const mjCHField& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCHField_*>(this) = static_cast<const mjCHField_&>(other); |
| | *static_cast<mjsHField*>(this) = static_cast<const mjsHField&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCHField::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.file = &spec_file_; |
| | spec.content_type = &spec_content_type_; |
| | spec.userdata = &spec_userdata_; |
| | spec.info = &info; |
| | file = nullptr; |
| | content_type = nullptr; |
| | userdata = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCHField::CopyFromSpec() { |
| | *static_cast<mjsHField*>(this) = spec; |
| | file_ = spec_file_; |
| | content_type_ = spec_content_type_; |
| | userdata_ = spec_userdata_; |
| |
|
| | |
| | data.clear(); |
| | if (!file_.empty()) { |
| | nrow = 0; |
| | ncol = 0; |
| | } |
| |
|
| | |
| | if (name.empty()) { |
| | std::string stripped = mjuu_strippath(file_); |
| | name = mjuu_stripext(stripped); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCHField::NameSpace(const mjCModel* m) { |
| | |
| | if (name.empty()) { |
| | std::string stripped = mjuu_strippath(spec_file_); |
| | name = mjuu_stripext(stripped); |
| | } |
| | mjCBase::NameSpace(m); |
| | if (modelfiledir_.empty()) { |
| | modelfiledir_ = FilePath(m->spec_modelfiledir_); |
| | } |
| | if (meshdir_.empty()) { |
| | meshdir_ = FilePath(m->spec_meshdir_); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCHField::~mjCHField() { |
| | data.clear(); |
| | userdata_.clear(); |
| | spec_userdata_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCHField::LoadCustom(mjResource* resource) { |
| | |
| | const void* buffer = 0; |
| | int buffer_sz = mju_readResource(resource, &buffer); |
| |
|
| | if (buffer_sz < 1) { |
| | throw mjCError(this, "could not read hfield file '%s'", resource->name); |
| | } else if (!buffer_sz) { |
| | throw mjCError(this, "empty hfield file '%s'", resource->name); |
| | } |
| |
|
| |
|
| | if (buffer_sz < 2*sizeof(int)) { |
| | throw mjCError(this, "hfield missing header '%s'", resource->name); |
| | } |
| |
|
| | |
| | int* pint = (int*)buffer; |
| | nrow = pint[0]; |
| | ncol = pint[1]; |
| |
|
| | |
| | if (nrow < 1 || ncol < 1) { |
| | throw mjCError(this, "non-positive hfield dimensions in file '%s'", resource->name); |
| | } |
| |
|
| | |
| | if (buffer_sz != nrow*ncol*sizeof(float)+8) { |
| | throw mjCError(this, "unexpected file size in file '%s'", resource->name); |
| | } |
| |
|
| | |
| | data.assign(nrow*ncol, 0); |
| | if (data.empty()) { |
| | throw mjCError(this, "could not allocate buffers in hfield"); |
| | } |
| |
|
| | |
| | memcpy(data.data(), (void*)(pint+2), nrow*ncol*sizeof(float)); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCHField::LoadPNG(mjResource* resource) { |
| | PNGImage image = PNGImage::Load(this, resource, LCT_GREY); |
| |
|
| | ncol = image.Width(); |
| | nrow = image.Height(); |
| |
|
| | |
| | data.reserve(nrow * ncol); |
| | for (int r = 0; r < nrow; r++) { |
| | for (int c = 0; c < ncol; c++) { |
| | data.push_back((float) image[c + (nrow - 1 - r)*ncol]); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCHField::Compile(const mjVFS* vfs) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (!userdata_.empty()) { |
| | if (nrow*ncol != userdata_.size()) { |
| | throw mjCError(this, "elevation data length must match nrow*ncol"); |
| | } |
| | data.assign(nrow*ncol, 0); |
| | if (data.empty()) { |
| | throw mjCError(this, "could not allocate buffers in hfield"); |
| | } |
| | memcpy(data.data(), userdata_.data(), nrow*ncol*sizeof(float)); |
| | } |
| |
|
| | |
| | for (int i=0; i < 4; i++) |
| | if (size[i] <= 0) |
| | throw mjCError(this, "size parameter is not positive in hfield"); |
| |
|
| | |
| | if (model->strippath) { |
| | file_ = mjuu_strippath(file_); |
| | } |
| |
|
| | |
| | if (!file_.empty()) { |
| | |
| | if (nrow || ncol || !data.empty()) { |
| | throw mjCError(this, "hfield specified from file and manually"); |
| | } |
| |
|
| | std::string asset_type = GetAssetContentType(file_, content_type_); |
| |
|
| | |
| | if (asset_type.empty()) { |
| | asset_type = "image/vnd.mujoco.hfield"; |
| | } |
| |
|
| | if (asset_type != "image/png" && asset_type != "image/vnd.mujoco.hfield") { |
| | throw mjCError(this, "unsupported content type: '%s'", asset_type.c_str()); |
| | } |
| |
|
| | |
| | if (modelfiledir_.empty()) { |
| | modelfiledir_ = FilePath(model->modelfiledir_); |
| | } |
| | if (meshdir_.empty()) { |
| | meshdir_ = FilePath(model->meshdir_); |
| | } |
| |
|
| | FilePath filename = meshdir_ + FilePath(file_); |
| | mjResource* resource = LoadResource(modelfiledir_.Str(), filename.Str(), vfs); |
| |
|
| | try { |
| | if (asset_type == "image/png") { |
| | LoadPNG(resource); |
| | } else { |
| | LoadCustom(resource); |
| | } |
| | mju_closeResource(resource); |
| | } catch(mjCError err) { |
| | mju_closeResource(resource); |
| | throw err; |
| | } |
| | } |
| |
|
| | |
| | if (nrow < 1 || ncol < 1 || data.empty()) { |
| | throw mjCError(this, "hfield not specified"); |
| | } |
| |
|
| | |
| | float emin = 1E+10, emax = -1E+10; |
| | for (int i = 0; i < nrow*ncol; i++) { |
| | emin = std::min(emin, data[i]); |
| | emax = std::max(emax, data[i]); |
| | } |
| | if (emin > emax) { |
| | throw mjCError(this, "invalid data range in hfield '%s'", file_.c_str()); |
| | } |
| | for (int i=0; i < nrow*ncol; i++) { |
| | data[i] -= emin; |
| | if (emax-emin > mjEPS) { |
| | data[i] /= (emax - emin); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCTexture::mjCTexture(mjCModel* _model) { |
| | mjs_defaultTexture(&spec); |
| | elemtype = mjOBJ_TEXTURE; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_file_.clear(); |
| | spec_content_type_.clear(); |
| |
|
| | |
| | spec_cubefiles_.assign(6, ""); |
| |
|
| | |
| | data_.clear(); |
| | clear_data_ = false; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCTexture::mjCTexture(const mjCTexture& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCTexture& mjCTexture::operator=(const mjCTexture& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCTexture_*>(this) = static_cast<const mjCTexture_&>(other); |
| | clear_data_ = other.clear_data_; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTexture::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.file = &spec_file_; |
| | spec.data = &data_; |
| | spec.content_type = &spec_content_type_; |
| | spec.cubefiles = &spec_cubefiles_; |
| | spec.info = &info; |
| | file = nullptr; |
| | content_type = nullptr; |
| | cubefiles = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTexture::CopyFromSpec() { |
| | *static_cast<mjsTexture*>(this) = spec; |
| | file_ = spec_file_; |
| | content_type_ = spec_content_type_; |
| | cubefiles_ = spec_cubefiles_; |
| |
|
| | if (clear_data_) { |
| | |
| | data_.clear(); |
| | } |
| |
|
| | |
| | if (name.empty()) { |
| | std::string stripped = mjuu_strippath(file_); |
| | name = mjuu_stripext(stripped); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCTexture::NameSpace(const mjCModel* m) { |
| | |
| | if (name.empty()) { |
| | std::string stripped = mjuu_strippath(spec_file_); |
| | name = mjuu_stripext(stripped); |
| | } |
| | mjCBase::NameSpace(m); |
| | if (modelfiledir_.empty()) { |
| | modelfiledir_ = FilePath(m->spec_modelfiledir_); |
| | } |
| | if (texturedir_.empty()) { |
| | texturedir_ = FilePath(m->spec_texturedir_); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCTexture::~mjCTexture() { |
| | data_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void randomdot(std::byte* rgb, const double* markrgb, |
| | int width, int height, double probability) { |
| | |
| | std::mt19937_64 rng; |
| | rng.seed(42); |
| | std::uniform_real_distribution<double> dist(0, 1); |
| |
|
| | |
| | for (int r=0; r < height; r++) { |
| | for (int c=0; c < width; c++) { |
| | if (dist(rng) < probability) { |
| | for (int j=0; j < 3; j++) { |
| | rgb[3*(r*width+c)+j] = (std::byte)(255*markrgb[j]); |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void interp(std::byte* rgb, const double* rgb1, const double* rgb2, double pos) { |
| | const double correction = 1.0/sqrt(2); |
| | double alpha = 0.5*(1 + pos/sqrt(1+pos*pos)/correction); |
| | if (alpha < 0) { |
| | alpha = 0; |
| | } else if (alpha > 1) { |
| | alpha = 1; |
| | } |
| |
|
| | for (int j=0; j < 3; j++) { |
| | rgb[j] = (std::byte)(255*(alpha*rgb1[j] + (1-alpha)*rgb2[j])); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void checker(std::byte* rgb, const std::byte* RGB1, const std::byte* RGB2, |
| | int width, int height) { |
| | for (int r=0; r < height/2; r++) { |
| | for (int c=0; c < width/2; c++) { |
| | memcpy(rgb+3*(r*width+c), RGB1, 3); |
| | } |
| | } |
| | for (int r=height/2; r < height; r++) { |
| | for (int c=width/2; c < width; c++) { |
| | memcpy(rgb+3*(r*width+c), RGB1, 3); |
| | } |
| | } |
| | for (int r=0; r < height/2; r++) { |
| | for (int c=width/2; c < width; c++) { |
| | memcpy(rgb+3*(r*width+c), RGB2, 3); |
| | } |
| | } |
| | for (int r=height/2; r < height; r++) { |
| | for (int c=0; c < width/2; c++) { |
| | memcpy(rgb+3*(r*width+c), RGB2, 3); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::Builtin2D(void) { |
| | std::byte RGB1[3], RGB2[3], RGBm[3]; |
| | |
| | for (int j=0; j < 3; j++) { |
| | RGB1[j] = (std::byte)(255*rgb1[j]); |
| | RGB2[j] = (std::byte)(255*rgb2[j]); |
| | RGBm[j] = (std::byte)(255*markrgb[j]); |
| | } |
| |
|
| | |
| |
|
| | |
| | if (builtin == mjBUILTIN_GRADIENT) { |
| | for (int r=0; r < height; r++) { |
| | for (int c=0; c < width; c++) { |
| | |
| | double x = 2*c/((double)(width-1)) - 1; |
| | double y = 1 - 2*r/((double)(height-1)); |
| | double pos = 2*sqrt(x*x+y*y) - 1; |
| |
|
| | |
| | interp(data_.data() + 3*(r*width+c), rgb2, rgb1, pos); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (builtin == mjBUILTIN_CHECKER) { |
| | checker(data_.data(), RGB1, RGB2, width, height); |
| | } |
| |
|
| | |
| | else if (builtin == mjBUILTIN_FLAT) { |
| | for (int r=0; r < height; r++) { |
| | for (int c=0; c < width; c++) { |
| | memcpy(data_.data()+3*(r*width+c), RGB1, 3); |
| | } |
| | } |
| | } |
| |
|
| | |
| |
|
| | |
| | if (mark == mjMARK_EDGE) { |
| | for (int r=0; r < height; r++) { |
| | memcpy(data_.data()+3*(r*width+0), RGBm, 3); |
| | memcpy(data_.data()+3*(r*width+width-1), RGBm, 3); |
| | } |
| | for (int c=0; c < width; c++) { |
| | memcpy(data_.data()+3*(0*width+c), RGBm, 3); |
| | memcpy(data_.data()+3*((height-1)*width+c), RGBm, 3); |
| | } |
| | } |
| |
|
| | |
| | else if (mark == mjMARK_CROSS) { |
| | for (int r=0; r < height; r++) { |
| | memcpy(data_.data()+3*(r*width+width/2), RGBm, 3); |
| | } |
| | for (int c=0; c < width; c++) { |
| | memcpy(data_.data()+3*(height/2*width+c), RGBm, 3); |
| | } |
| | } |
| |
|
| | |
| | else if (mark == mjMARK_RANDOM && random > 0) { |
| | randomdot(data_.data(), markrgb, width, height, random); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::BuiltinCube(void) { |
| | std::byte RGB1[3], RGB2[3], RGBm[3], RGBi[3]; |
| | int w = width; |
| | if (w > std::numeric_limits<int>::max() / w) { |
| | throw mjCError(this, "Cube texture width is too large."); |
| | } |
| | int ww = width*width; |
| |
|
| | |
| | for (int j = 0; j < 3; j++) { |
| | RGB1[j] = (std::byte)(255 * rgb1[j]); |
| | RGB2[j] = (std::byte)(255 * rgb2[j]); |
| | RGBm[j] = (std::byte)(255 * markrgb[j]); |
| | } |
| |
|
| | |
| |
|
| | |
| | if (builtin == mjBUILTIN_GRADIENT) { |
| | if (ww > std::numeric_limits<int>::max() / 18) { |
| | throw mjCError(this, "Gradient texture width is too large."); |
| | } |
| | for (int r = 0; r < w; r++) { |
| | for (int c = 0; c < w; c++) { |
| | |
| | double x = 2 * c / ((double)(w - 1)) - 1; |
| | double y = 1 - 2 * r / ((double)(w - 1)); |
| |
|
| | |
| | double elside = asin(y / sqrt(1 + x * x + y * y)) / (0.5 * mjPI); |
| | double elup = 1 - acos(1.0 / sqrt(1 + x * x + y * y)) / (0.5 * mjPI); |
| |
|
| | |
| | interp(RGBi, rgb1, rgb2, elside); |
| | memcpy(data_.data() + 0 * 3 * ww + 3 * (r * w + c), RGBi, 3); |
| | memcpy(data_.data() + 1 * 3 * ww + 3 * (r * w + c), RGBi, 3); |
| | memcpy(data_.data() + 4 * 3 * ww + 3 * (r * w + c), RGBi, 3); |
| | memcpy(data_.data() + 5 * 3 * ww + 3 * (r * w + c), RGBi, 3); |
| |
|
| | |
| | interp(data_.data() + 2 * 3 * ww + 3 * (r * w + c), rgb1, rgb2, elup); |
| | interp(data_.data() + 3 * 3 * ww + 3 * (r * w + c), rgb1, rgb2, -elup); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (builtin == mjBUILTIN_CHECKER) { |
| | checker(data_.data() + 0 * 3 * ww, RGB1, RGB2, w, w); |
| | checker(data_.data() + 1 * 3 * ww, RGB1, RGB2, w, w); |
| | checker(data_.data() + 2 * 3 * ww, RGB1, RGB2, w, w); |
| | checker(data_.data() + 3 * 3 * ww, RGB1, RGB2, w, w); |
| | checker(data_.data() + 4 * 3 * ww, RGB2, RGB1, w, w); |
| | checker(data_.data() + 5 * 3 * ww, RGB2, RGB1, w, w); |
| | } |
| |
|
| | |
| | else if (builtin == mjBUILTIN_FLAT) { |
| | for (int r = 0; r < w; r++) { |
| | for (int c = 0; c < w; c++) { |
| | |
| | memcpy(data_.data() + 0 * 3 * ww + 3 * (r * w + c), RGB1, 3); |
| | memcpy(data_.data() + 1 * 3 * ww + 3 * (r * w + c), RGB1, 3); |
| | memcpy(data_.data() + 2 * 3 * ww + 3 * (r * w + c), RGB1, 3); |
| | memcpy(data_.data() + 4 * 3 * ww + 3 * (r * w + c), RGB1, 3); |
| | memcpy(data_.data() + 5 * 3 * ww + 3 * (r * w + c), RGB1, 3); |
| |
|
| | |
| | memcpy(data_.data() + 3 * 3 * ww + 3 * (r * w + c), RGB2, 3); |
| | } |
| | } |
| | } |
| |
|
| | |
| |
|
| | |
| | if (mark == mjMARK_EDGE) { |
| | for (int j = 0; j < 6; j++) { |
| | for (int r = 0; r < w; r++) { |
| | memcpy(data_.data() + j * 3 * ww + 3 * (r * w + 0), RGBm, 3); |
| | memcpy(data_.data() + j * 3 * ww + 3 * (r * w + w - 1), RGBm, 3); |
| | } |
| | for (int c = 0; c < w; c++) { |
| | memcpy(data_.data() + j * 3 * ww + 3 * (0 * w + c), RGBm, 3); |
| | memcpy(data_.data() + j * 3 * ww + 3 * ((w - 1) * w + c), RGBm, 3); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (mark == mjMARK_CROSS) { |
| | for (int j = 0; j < 6; j++) { |
| | for (int r = 0; r < w; r++) { |
| | memcpy(data_.data() + j * 3 * ww + 3 * (r * w + w / 2), RGBm, 3); |
| | } |
| | for (int c = 0; c < w; c++) { |
| | memcpy(data_.data() + j * 3 * ww + 3 * (w / 2 * w + c), RGBm, 3); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (mark == mjMARK_RANDOM && random > 0) { |
| | randomdot(data_.data(), markrgb, w, height, random); |
| | } |
| | } |
| |
|
| | |
| | void mjCTexture::LoadPNG(mjResource* resource, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb) { |
| | LodePNGColorType color_type; |
| | if (nchannel == 4) { |
| | color_type = LCT_RGBA; |
| | } else if (nchannel == 3) { |
| | color_type = LCT_RGB; |
| | } else if (nchannel == 1) { |
| | color_type = LCT_GREY; |
| | } else { |
| | throw mjCError(this, "Unsupported number of channels: %s", |
| | std::to_string(nchannel).c_str()); |
| | } |
| | PNGImage png_image = PNGImage::Load(this, resource, color_type); |
| | w = png_image.Width(); |
| | h = png_image.Height(); |
| | is_srgb = png_image.IsSRGB(); |
| | image = png_image.MoveData(); |
| | } |
| |
|
| | |
| | void mjCTexture::LoadKTX(mjResource* resource, |
| | std::vector<unsigned char>& image, unsigned int& w, |
| | unsigned int& h, bool& is_srgb) { |
| | const void* buffer = 0; |
| | int buffer_sz = mju_readResource(resource, &buffer); |
| |
|
| | |
| | if (buffer_sz < 0) { |
| | throw mjCError(this, "could not read texture file '%s'", resource->name); |
| | } else if (!buffer_sz) { |
| | throw mjCError(this, "texture file is empty: '%s'", resource->name); |
| | } |
| |
|
| | w = buffer_sz; |
| | h = 1; |
| | is_srgb = false; |
| |
|
| | image.resize(buffer_sz); |
| | memcpy(image.data(), buffer, buffer_sz); |
| | } |
| |
|
| | |
| | void mjCTexture::LoadCustom(mjResource* resource, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb) { |
| | const void* buffer = 0; |
| | int buffer_sz = mju_readResource(resource, &buffer); |
| |
|
| | |
| | if (buffer_sz < 0) { |
| | throw mjCError(this, "could not read texture file '%s'", resource->name); |
| | } else if (!buffer_sz) { |
| | throw mjCError(this, "texture file is empty: '%s'", resource->name); |
| | } |
| |
|
| |
|
| | |
| | int* pint = (int*)buffer; |
| | w = pint[0]; |
| | h = pint[1]; |
| |
|
| | |
| | is_srgb = false; |
| |
|
| | |
| | if (w < 1 || h < 1) { |
| | throw mjCError(this, "Non-PNG texture, assuming custom binary file format,\n" |
| | "non-positive texture dimensions in file '%s'", resource->name); |
| | } |
| |
|
| | |
| | if (buffer_sz != 2*sizeof(int) + w*h*3*sizeof(char)) { |
| | throw mjCError(this, "Non-PNG texture, assuming custom binary file format,\n" |
| | "unexpected file size in file '%s'", resource->name); |
| | } |
| |
|
| | |
| | image.resize(w*h*3); |
| | memcpy(image.data(), (void*)(pint+2), w*h*3*sizeof(char)); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::LoadFlip(std::string filename, const mjVFS* vfs, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb) { |
| | std::string asset_type = GetAssetContentType(filename, content_type_); |
| |
|
| | |
| | if (asset_type.empty()) { |
| | asset_type = "image/vnd.mujoco.texture"; |
| | } |
| |
|
| | if (asset_type != "image/png" && asset_type != "image/ktx" && asset_type != "image/vnd.mujoco.texture") { |
| | throw mjCError(this, "unsupported content type: '%s'", asset_type.c_str()); |
| | } |
| |
|
| | mjResource* resource = LoadResource(modelfiledir_.Str(), filename, vfs); |
| |
|
| | try { |
| | if (asset_type == "image/png") { |
| | LoadPNG(resource, image, w, h, is_srgb); |
| | } else if (asset_type == "image/ktx") { |
| | if (hflip || vflip) { |
| | throw mjCError(this, "cannot flip KTX textures"); |
| | } |
| | LoadKTX(resource, image, w, h, is_srgb); |
| | } else { |
| | LoadCustom(resource, image, w, h, is_srgb); |
| | } |
| | mju_closeResource(resource); |
| | } catch(mjCError err) { |
| | mju_closeResource(resource); |
| | throw err; |
| | } |
| |
|
| | |
| | if (hflip) { |
| | if (nchannel != 3) { |
| | throw mjCError( |
| | this, "currently only 3-channel textures support horizontal flip"); |
| | } |
| | for (int r=0; r < h; r++) { |
| | for (int c=0; c < w/2; c++) { |
| | int c1 = w-1-c; |
| | unsigned char tmp[3] = { |
| | image[3*(r*w+c)], |
| | image[3*(r*w+c)+1], |
| | image[3*(r*w+c)+2] |
| | }; |
| |
|
| | image[3*(r*w+c)] = image[3*(r*w+c1)]; |
| | image[3*(r*w+c)+1] = image[3*(r*w+c1)+1]; |
| | image[3*(r*w+c)+2] = image[3*(r*w+c1)+2]; |
| |
|
| | image[3*(r*w+c1)] = tmp[0]; |
| | image[3*(r*w+c1)+1] = tmp[1]; |
| | image[3*(r*w+c1)+2] = tmp[2]; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (vflip) { |
| | if (nchannel != 3) { |
| | throw mjCError( |
| | this, "currently only 3-channel textures support vertical flip"); |
| | } |
| | for (int r=0; r < h/2; r++) { |
| | for (int c=0; c < w; c++) { |
| | int r1 = h-1-r; |
| | unsigned char tmp[3] = { |
| | image[3*(r*w+c)], |
| | image[3*(r*w+c)+1], |
| | image[3*(r*w+c)+2] |
| | }; |
| |
|
| | image[3*(r*w+c)] = image[3*(r1*w+c)]; |
| | image[3*(r*w+c)+1] = image[3*(r1*w+c)+1]; |
| | image[3*(r*w+c)+2] = image[3*(r1*w+c)+2]; |
| |
|
| | image[3*(r1*w+c)] = tmp[0]; |
| | image[3*(r1*w+c)+1] = tmp[1]; |
| | image[3*(r1*w+c)+2] = tmp[2]; |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::Load2D(std::string filename, const mjVFS* vfs) { |
| | |
| | unsigned int w, h; |
| | bool is_srgb; |
| | std::vector<unsigned char> image; |
| | LoadFlip(filename, vfs, image, w, h, is_srgb); |
| |
|
| | |
| | width = w; |
| | height = h; |
| | if (colorspace == mjCOLORSPACE_AUTO) { |
| | colorspace = is_srgb ? mjCOLORSPACE_SRGB : mjCOLORSPACE_LINEAR; |
| | } |
| |
|
| | |
| | std::int64_t size = static_cast<std::int64_t>(width)*height; |
| | if (size >= std::numeric_limits<int>::max() / nchannel || size <= 0) { |
| | throw mjCError(this, "Texture too large"); |
| | } |
| | try { |
| | data_.assign(nchannel*size, std::byte(0)); |
| | } catch (const std::bad_alloc& e) { |
| | throw mjCError(this, "Could not allocate memory for texture '%s' (id %d)", |
| | (const char*)file_.c_str(), id); |
| | } |
| | memcpy(data_.data(), image.data(), nchannel*size); |
| | image.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::LoadCubeSingle(std::string filename, const mjVFS* vfs) { |
| | |
| | if (gridsize[0] < 1 || gridsize[1] < 1 || gridsize[0]*gridsize[1] > 12) { |
| | throw mjCError(this, "gridsize must be non-zero and no more than 12 squares in texture"); |
| | } |
| |
|
| | |
| | unsigned int w, h; |
| | bool is_srgb; |
| | std::vector<unsigned char> image; |
| | LoadFlip(filename, vfs, image, w, h, is_srgb); |
| |
|
| | if (colorspace == mjCOLORSPACE_AUTO) { |
| | colorspace = is_srgb ? mjCOLORSPACE_SRGB : mjCOLORSPACE_LINEAR; |
| | } |
| |
|
| | |
| | if (w/gridsize[1] != h/gridsize[0] || (w%gridsize[1]) || (h%gridsize[0])) { |
| | throw mjCError(this, |
| | "PNG size must be integer multiple of gridsize in texture '%s' (id %d)", |
| | (const char*)file_.c_str(), id); |
| | } |
| |
|
| | |
| | if (gridsize[0] == 1 && gridsize[1] == 1) { |
| | width = height = w; |
| | } else { |
| | width = w/gridsize[1]; |
| | if (width >= std::numeric_limits<int>::max()/6) { |
| | throw mjCError(this, "Invalid width of cube texture"); |
| | } |
| | height = 6*width; |
| | } |
| |
|
| | |
| | std::int64_t size = static_cast<std::int64_t>(width)*height; |
| | if (size >= std::numeric_limits<int>::max() / 3 || size <= 0) { |
| | throw mjCError(this, "Cube texture too large"); |
| | } |
| | try { |
| | data_.assign(3*size, std::byte(0)); |
| | } catch (const std::bad_alloc& e) { |
| | throw mjCError(this, |
| | "Could not allocate memory for texture '%s' (id %d)", |
| | (const char*)file_.c_str(), id); |
| | } |
| |
|
| | |
| | if (gridsize[0] == 1 && gridsize[1] == 1) { |
| | memcpy(data_.data(), image.data(), 3*width*width); |
| | } |
| |
|
| | |
| | else { |
| | |
| | int loaded[6] = {0, 0, 0, 0, 0, 0}; |
| |
|
| | |
| | for (int k=0; k < gridsize[0]*gridsize[1]; k++) { |
| | |
| | int i = -1; |
| | if (gridlayout[k] == 'R') { |
| | i = 0; |
| | } else if (gridlayout[k] == 'L') { |
| | i = 1; |
| | } else if (gridlayout[k] == 'U') { |
| | i = 2; |
| | } else if (gridlayout[k] == 'D') { |
| | i = 3; |
| | } else if (gridlayout[k] == 'F') { |
| | i = 4; |
| | } else if (gridlayout[k] == 'B') { |
| | i = 5; |
| | } else if (gridlayout[k] != '.') |
| | throw mjCError(this, "gridlayout symbol is not among '.RLUDFB' in texture"); |
| |
|
| | |
| | if (i >= 0) { |
| | |
| | int rstart = width*(k/gridsize[1]); |
| | int cstart = width*(k%gridsize[1]); |
| | for (int j=0; j < width; j++) { |
| | memcpy(data_.data()+i*3*width*width+j*3*width, image.data()+(j+rstart)*3*w+3*cstart, 3*width); |
| | } |
| |
|
| | |
| | loaded[i] = 1; |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < 6; i++) { |
| | if (!loaded[i]) { |
| | for (int k=0; k < width; k++) { |
| | for (int s=0; s < width; s++) { |
| | for (int j=0; j < 3; j++) { |
| | data_[i*3*width*width + 3*(k*width+s) + j] = (std::byte)(255*rgb1[j]); |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | image.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::LoadCubeSeparate(const mjVFS* vfs) { |
| | |
| | int loaded[6] = {0, 0, 0, 0, 0, 0}; |
| |
|
| | |
| | for (int i=0; i < 6; i++) { |
| | if (!cubefiles_[i].empty()) { |
| | |
| | if (model->strippath) { |
| | cubefiles_[i] = mjuu_strippath(cubefiles_[i]); |
| | } |
| |
|
| | |
| | FilePath filename = texturedir_ + FilePath(cubefiles_[i]); |
| |
|
| | |
| | unsigned int w, h; |
| | bool is_srgb; |
| | std::vector<unsigned char> image; |
| | LoadFlip(filename.Str(), vfs, image, w, h, is_srgb); |
| |
|
| | |
| | if (colorspace == mjCOLORSPACE_AUTO) { |
| | colorspace = is_srgb ? mjCOLORSPACE_SRGB : mjCOLORSPACE_LINEAR; |
| | } |
| |
|
| | |
| | if (w != h) { |
| | throw mjCError(this, |
| | "Non-square PNG file '%s' in cube or skybox id %d", |
| | (const char*)cubefiles_[i].c_str(), id); |
| | } |
| |
|
| | |
| | if (data_.empty()) { |
| | width = w; |
| | if (width >= std::numeric_limits<int>::max()/6) { |
| | throw mjCError(this, "Invalid width of builtin texture"); |
| | } |
| | height = 6*width; |
| | std::int64_t size = static_cast<std::int64_t>(width)*height; |
| | if (size >= std::numeric_limits<int>::max() / 3 || size <= 0) { |
| | throw mjCError(this, "PNG texture too large"); |
| | } |
| | try { |
| | data_.assign(3*size, std::byte(0)); |
| | } catch (const std::bad_alloc& e) { |
| | throw mjCError(this, "Could not allocate memory for texture"); |
| | } |
| | } |
| |
|
| | |
| | else if (width != w) { |
| | throw mjCError(this, |
| | "PNG file '%s' has incompatible size in texture id %d", |
| | (const char*)cubefiles_[i].c_str(), id); |
| | } |
| |
|
| | |
| | memcpy(data_.data()+i*3*width*width, image.data(), 3*width*width); |
| | image.clear(); |
| |
|
| | |
| | loaded[i] = 1; |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < 6; i++) { |
| | if (!loaded[i]) { |
| | for (int k=0; k < width; k++) { |
| | for (int s=0; s < width; s++) { |
| | for (int j=0; j < 3; j++) { |
| | data_[i*3*width*width + 3*(k*width+s) + j] = (std::byte)(255*rgb1[j]); |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTexture::Compile(const mjVFS* vfs) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (modelfiledir_.empty()) { |
| | modelfiledir_ = FilePath(model->modelfiledir_); |
| | } |
| | if (texturedir_.empty()) { |
| | texturedir_ = FilePath(model->texturedir_); |
| | } |
| |
|
| | |
| | if (!data_.empty()) { |
| | if (data_.size() != nchannel*width*height) { |
| | throw mjCError(this, "Texture buffer has incorrect size, given %d expected %d", nullptr, |
| | data_.size(), nchannel * width * height); |
| | } |
| | return; |
| | } |
| |
|
| | |
| | else if (builtin != mjBUILTIN_NONE) { |
| | |
| | if (width < 1) { |
| | throw mjCError(this, "Invalid width of builtin texture"); |
| | } |
| |
|
| | |
| | if (type != mjTEXTURE_2D) { |
| | if (width >= std::numeric_limits<int>::max()/6) { |
| | throw mjCError(this, "Invalid width of builtin texture"); |
| | } |
| | height = 6*width; |
| | } else { |
| | if (height < 1) { |
| | throw mjCError(this, "Invalid height of builtin texture"); |
| | } |
| | } |
| |
|
| | std::int64_t size = static_cast<std::int64_t>(width)*height; |
| | if (size >= std::numeric_limits<int>::max() / nchannel || size <= 0) { |
| | throw mjCError(this, "Builtin texture too large"); |
| | } |
| | |
| | try { |
| | data_.assign(nchannel*size, std::byte(0)); |
| | } catch (const std::bad_alloc& e) { |
| | throw mjCError(this, "Could not allocate memory for texture"); |
| | } |
| |
|
| | |
| | if (type == mjTEXTURE_2D) { |
| | Builtin2D(); |
| | } else { |
| | BuiltinCube(); |
| | } |
| | } |
| |
|
| | |
| | else if (!file_.empty()) { |
| | |
| | if (model->strippath) { |
| | file_ = mjuu_strippath(file_); |
| | } |
| |
|
| | |
| | FilePath filename = texturedir_ + FilePath(file_); |
| |
|
| | |
| | if (type == mjTEXTURE_2D) { |
| | Load2D(filename.Str(), vfs); |
| | } else { |
| | LoadCubeSingle(filename.Str(), vfs); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | if (type == mjTEXTURE_2D) { |
| | throw mjCError(this, |
| | "Cannot load 2D texture from separate files, texture"); |
| | } |
| |
|
| | |
| | bool defined = false; |
| | for (int i=0; i < 6; i++) { |
| | if (!cubefiles_[i].empty()) { |
| | defined = true; |
| | break; |
| | } |
| | } |
| | if (!defined) { |
| | throw mjCError(this, |
| | "No cubefiles_ defined in cube or skybox texture"); |
| | } |
| |
|
| | |
| | LoadCubeSeparate(vfs); |
| | } |
| |
|
| | |
| | if (data_.empty()) { |
| | throw mjCError(this, "texture '%s' (id %d) was not specified", name.c_str(), id); |
| | } |
| |
|
| | |
| | clear_data_ = true; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCMaterial::mjCMaterial(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultMaterial(&spec); |
| | elemtype = mjOBJ_MATERIAL; |
| | textures_.assign(mjNTEXROLE, ""); |
| | spec_textures_.assign(mjNTEXROLE, ""); |
| |
|
| | |
| | for (int i=0; i < mjNTEXROLE; i++) { |
| | texid[i] = -1; |
| | } |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Material(); |
| | } |
| |
|
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCMaterial::mjCMaterial(const mjCMaterial& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCMaterial& mjCMaterial::operator=(const mjCMaterial& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCMaterial_*>(this) = static_cast<const mjCMaterial_&>(other); |
| | *static_cast<mjsMaterial*>(this) = static_cast<const mjsMaterial&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCMaterial::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.textures = &spec_textures_; |
| | spec.info = &info; |
| | textures = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCMaterial::CopyFromSpec() { |
| | *static_cast<mjsMaterial*>(this) = spec; |
| | textures_ = spec_textures_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCMaterial::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | for (int i=0; i < mjNTEXROLE; i++) { |
| | if (!spec_textures_[i].empty()) { |
| | spec_textures_[i] = m->prefix + spec_textures_[i] + m->suffix; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCMaterial::Compile(void) { |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCPair::mjCPair(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultPair(&spec); |
| | elemtype = mjOBJ_PAIR; |
| |
|
| | |
| | spec_geomname1_.clear(); |
| | spec_geomname2_.clear(); |
| |
|
| | |
| | geom1 = nullptr; |
| | geom2 = nullptr; |
| | signature = -1; |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Pair(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCPair::mjCPair(const mjCPair& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCPair& mjCPair::operator=(const mjCPair& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCPair_*>(this) = static_cast<const mjCPair_&>(other); |
| | *static_cast<mjsPair*>(this) = static_cast<const mjsPair&>(other); |
| | this->geom1 = nullptr; |
| | this->geom2 = nullptr; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCPair::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.geomname1 = &spec_geomname1_; |
| | spec.geomname2 = &spec_geomname2_; |
| | geomname1 = nullptr; |
| | geomname2 = nullptr; |
| | spec.info = &info; |
| | } |
| |
|
| |
|
| |
|
| | void mjCPair::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | prefix = m->prefix; |
| | suffix = m->suffix; |
| | } |
| |
|
| |
|
| |
|
| | void mjCPair::CopyFromSpec() { |
| | *static_cast<mjsPair*>(this) = spec; |
| | geomname1_ = spec_geomname1_; |
| | geomname2_ = spec_geomname2_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCPair::ResolveReferences(const mjCModel* m) { |
| | geomname1_ = prefix + geomname1_ + suffix; |
| | geomname2_ = prefix + geomname2_ + suffix; |
| | geom1 = (mjCGeom*)m->FindObject(mjOBJ_GEOM, geomname1_); |
| | geom2 = (mjCGeom*)m->FindObject(mjOBJ_GEOM, geomname2_); |
| |
|
| | if (!geom1 && geom2) { |
| | geomname1_ = spec_geomname1_; |
| | geom1 = (mjCGeom*)m->FindObject(mjOBJ_GEOM, geomname1_); |
| | } |
| | if (geom1 && !geom2) { |
| | geomname2_ = spec_geomname2_; |
| | geom2 = (mjCGeom*)m->FindObject(mjOBJ_GEOM, geomname2_); |
| | } |
| |
|
| | if (!geom1) { |
| | throw mjCError(this, "geom '%s' not found in collision %d", geomname1_.c_str(), id); |
| | } |
| | if (!geom2) { |
| | throw mjCError(this, "geom '%s' not found in collision %d", geomname2_.c_str(), id); |
| | } |
| |
|
| | spec_geomname1_ = geomname1_; |
| | spec_geomname2_ = geomname2_; |
| | prefix.clear(); |
| | suffix.clear(); |
| |
|
| | |
| | if (geom1->body->id > geom2->body->id) { |
| | std::string nametmp = geomname1_; |
| | geomname1_ = geomname2_; |
| | geomname2_ = nametmp; |
| |
|
| | mjCGeom* geomtmp = geom1; |
| | geom1 = geom2; |
| | geom2 = geomtmp; |
| | } |
| |
|
| | |
| | signature = ((geom1->body->id)<<16) + geom2->body->id; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCPair::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (condim != 1 && condim != 3 && condim != 4 && condim != 6) { |
| | throw mjCError(this, "invalid condim in contact pair"); |
| | } |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | geom1->SetNotVisual(); |
| | geom2->SetNotVisual(); |
| |
|
| | |
| | if (!mjuu_defined(margin)) { |
| | margin = std::max(geom1->margin, geom2->margin); |
| | } |
| |
|
| | |
| | if (!mjuu_defined(gap)) { |
| | gap = std::max(geom1->gap, geom2->gap); |
| | } |
| |
|
| | |
| | if (geom1->priority != geom2->priority) { |
| | mjCGeom* pgh = (geom1->priority > geom2->priority ? geom1 : geom2); |
| |
|
| | |
| | if (condim < 0) { |
| | condim = pgh->condim; |
| | } |
| |
|
| | |
| | if (!mjuu_defined(friction[0])) { |
| | friction[0] = friction[1] = pgh->friction[0]; |
| | friction[2] = pgh->friction[1]; |
| | friction[3] = friction[4] = pgh->friction[2]; |
| | } |
| |
|
| | |
| | if (!mjuu_defined(solref[0])) { |
| | for (int i=0; i < mjNREF; i++) { |
| | solref[i] = pgh->solref[i]; |
| | } |
| | } |
| |
|
| | |
| | if (!mjuu_defined(solimp[0])) { |
| | for (int i=0; i < mjNIMP; i++) { |
| | solimp[i] = pgh->solimp[i]; |
| | } |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | if (condim < 0) { |
| | condim = std::max(geom1->condim, geom2->condim); |
| | } |
| |
|
| | |
| | if (!mjuu_defined(friction[0])) { |
| | friction[0] = friction[1] = std::max(geom1->friction[0], geom2->friction[0]); |
| | friction[2] = std::max(geom1->friction[1], geom2->friction[1]); |
| | friction[3] = friction[4] = std::max(geom1->friction[2], geom2->friction[2]); |
| | } |
| |
|
| | |
| | double mix; |
| | if (geom1->solmix >= mjEPS && geom2->solmix >= mjEPS) { |
| | mix = geom1->solmix / (geom1->solmix + geom2->solmix); |
| | } else if (geom1->solmix < mjEPS && geom2->solmix < mjEPS) { |
| | mix = 0.5; |
| | } else if (geom1->solmix < mjEPS) { |
| | mix = 0.0; |
| | } else { |
| | mix = 1.0; |
| | } |
| |
|
| | |
| | if (!mjuu_defined(solref[0])) { |
| | |
| | if (solref[0] > 0) { |
| | for (int i=0; i < mjNREF; i++) { |
| | solref[i] = mix*geom1->solref[i] + (1-mix)*geom2->solref[i]; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int i=0; i < mjNREF; i++) { |
| | solref[i] = std::min(geom1->solref[i], geom2->solref[i]); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (!mjuu_defined(solimp[0])) { |
| | for (int i=0; i < mjNIMP; i++) { |
| | solimp[i] = mix*geom1->solimp[i] + (1-mix)*geom2->solimp[i]; |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCBodyPair::mjCBodyPair(mjCModel* _model) { |
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | elemtype = mjOBJ_EXCLUDE; |
| |
|
| | |
| | spec_bodyname1_.clear(); |
| | spec_bodyname2_.clear(); |
| |
|
| | |
| | body1 = body2 = signature = -1; |
| |
|
| | PointToLocal(); |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCBodyPair::mjCBodyPair(const mjCBodyPair& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCBodyPair& mjCBodyPair::operator=(const mjCBodyPair& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCBodyPair_*>(this) = static_cast<const mjCBodyPair_&>(other); |
| | *static_cast<mjsExclude*>(this) = static_cast<const mjsExclude&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBodyPair::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.bodyname1 = &spec_bodyname1_; |
| | spec.bodyname2 = &spec_bodyname2_; |
| | spec.info = &info; |
| | bodyname1 = nullptr; |
| | bodyname2 = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBodyPair::NameSpace(const mjCModel* m) { |
| | if (!name.empty()) { |
| | name = m->prefix + name + m->suffix; |
| | } |
| | prefix = m->prefix; |
| | suffix = m->suffix; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBodyPair::CopyFromSpec() { |
| | *static_cast<mjsExclude*>(this) = spec; |
| | bodyname1_ = spec_bodyname1_; |
| | bodyname2_ = spec_bodyname2_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCBodyPair::ResolveReferences(const mjCModel* m) { |
| | bodyname1_ = prefix + bodyname1_ + suffix; |
| | bodyname2_ = prefix + bodyname2_ + suffix; |
| | mjCBody* pb1 = (mjCBody*)m->FindObject(mjOBJ_BODY, bodyname1_); |
| | mjCBody* pb2 = (mjCBody*)m->FindObject(mjOBJ_BODY, bodyname2_); |
| |
|
| | if (!pb1 && pb2) { |
| | bodyname1_ = spec_bodyname1_; |
| | pb1 = (mjCBody*)m->FindObject(mjOBJ_BODY, bodyname1_); |
| | } |
| | if (pb1 && !pb2) { |
| | bodyname2_ = spec_bodyname2_; |
| | pb2 = (mjCBody*)m->FindObject(mjOBJ_BODY, bodyname2_); |
| | } |
| |
|
| | if (!pb1) { |
| | throw mjCError(this, "body '%s' not found in bodypair %d", bodyname1_.c_str(), id); |
| | } |
| | if (!pb2) { |
| | throw mjCError(this, "body '%s' not found in bodypair %d", bodyname2_.c_str(), id); |
| | } |
| |
|
| | spec_bodyname1_ = bodyname1_; |
| | spec_bodyname2_ = bodyname2_; |
| | prefix.clear(); |
| | suffix.clear(); |
| |
|
| | |
| | if (pb1->id > pb2->id) { |
| | std::string nametmp = bodyname1_; |
| | bodyname1_ = bodyname2_; |
| | bodyname2_ = nametmp; |
| |
|
| | mjCBody* bodytmp = pb1; |
| | pb1 = pb2; |
| | pb2 = bodytmp; |
| | } |
| |
|
| | |
| | body1 = pb1->id; |
| | body2 = pb2->id; |
| | signature = (body1<<16) + body2; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCBodyPair::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | ResolveReferences(model); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCEquality::mjCEquality(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultEquality(&spec); |
| | elemtype = mjOBJ_EQUALITY; |
| |
|
| | |
| | spec_name1_.clear(); |
| | spec_name2_.clear(); |
| | obj1id = obj2id = -1; |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Equality(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCEquality::mjCEquality(const mjCEquality& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCEquality& mjCEquality::operator=(const mjCEquality& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCEquality_*>(this) = static_cast<const mjCEquality_&>(other); |
| | *static_cast<mjsEquality*>(this) = static_cast<const mjsEquality&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCEquality::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.name1 = &spec_name1_; |
| | spec.name2 = &spec_name2_; |
| | spec.info = &info; |
| | name1 = nullptr; |
| | name2 = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCEquality::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!spec_name1_.empty()) { |
| | spec_name1_ = m->prefix + spec_name1_ + m->suffix; |
| | } |
| | if (!spec_name2_.empty()) { |
| | spec_name2_ = m->prefix + spec_name2_ + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCEquality::CopyFromSpec() { |
| | *static_cast<mjsEquality*>(this) = spec; |
| | name1_ = spec_name1_; |
| | name2_ = spec_name2_; |
| | } |
| |
|
| |
|
| |
|
| | void mjCEquality::ResolveReferences(const mjCModel* m) { |
| | mjtObj object_type; |
| | mjCBase *px1, *px2; |
| | mjtJoint jt1, jt2; |
| |
|
| | |
| | if (type == mjEQ_WELD) { |
| | if (objtype != mjOBJ_SITE && objtype != mjOBJ_BODY) { |
| | throw mjCError(this, "weld constraint supports only sites and bodies"); |
| | } |
| | object_type = objtype; |
| | } else if (type == mjEQ_CONNECT) { |
| | if (objtype != mjOBJ_SITE && objtype != mjOBJ_BODY) { |
| | throw mjCError(this, "connect constraint supports only sites and bodies"); |
| | } |
| | object_type = objtype; |
| | } else if (type == mjEQ_JOINT) { |
| | object_type = mjOBJ_JOINT; |
| | } else if (type == mjEQ_TENDON) { |
| | object_type = mjOBJ_TENDON; |
| | } else if (type == mjEQ_FLEX) { |
| | object_type = mjOBJ_FLEX; |
| | } else { |
| | throw mjCError(this, "invalid type in equality constraint"); |
| | } |
| |
|
| | |
| | px1 = m->FindObject(object_type, name1_); |
| | if (!px1) { |
| | throw mjCError(this, "unknown element '%s' in equality constraint", name1_.c_str()); |
| | } |
| | obj1id = px1->id; |
| |
|
| | |
| | if (!name2_.empty()) { |
| | px2 = m->FindObject(object_type, name2_); |
| | if (!px2) { |
| | throw mjCError(this, "unknown element '%s' in equality constraint %d", name2_.c_str(), id); |
| | } |
| | obj2id = px2->id; |
| | } else { |
| | |
| | obj2id = -1; |
| | px2 = nullptr; |
| | } |
| |
|
| | |
| | if (object_type == mjOBJ_BODY && obj2id == -1) { |
| | obj2id = 0; |
| | } |
| |
|
| | |
| | if (obj1id == obj2id) { |
| | throw mjCError(this, "element '%s' is repeated in equality constraint %d", name1_.c_str(), id); |
| | } |
| |
|
| | |
| | if (type == mjEQ_JOINT) { |
| | jt1 = ((mjCJoint*)px1)->type; |
| | jt2 = (px2 ? ((mjCJoint*)px2)->type : mjJNT_HINGE); |
| | if ((jt1 != mjJNT_HINGE && jt1 != mjJNT_SLIDE) || |
| | (jt2 != mjJNT_HINGE && jt2 != mjJNT_SLIDE)) { |
| | throw mjCError(this, "only HINGE and SLIDE joint allowed in constraint"); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCEquality::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | if (type == mjEQ_FLEX && model->Flexes()[obj1id]->rigid) { |
| | throw mjCError(this, "rigid flex '%s' in equality constraint %d", name1_.c_str(), id); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCTendon::mjCTendon(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultTendon(&spec); |
| | elemtype = mjOBJ_TENDON; |
| |
|
| | |
| | spec_material_.clear(); |
| | spec_userdata_.clear(); |
| | path.clear(); |
| | matid = -1; |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Tendon(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCTendon::mjCTendon(const mjCTendon& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCTendon& mjCTendon::operator=(const mjCTendon& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCTendon_*>(this) = static_cast<const mjCTendon_&>(other); |
| | *static_cast<mjsTendon*>(this) = static_cast<const mjsTendon&>(other); |
| | for (int i=0; i < other.path.size(); i++) { |
| | path.push_back(new mjCWrap(*other.path[i])); |
| | path.back()->tendon = this; |
| | } |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | bool mjCTendon::is_limited() const { |
| | return islimited(limited, range); |
| | } |
| | bool mjCTendon::is_actfrclimited() const { |
| | return islimited(actfrclimited, actfrcrange); |
| | } |
| |
|
| | void mjCTendon::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.material = &spec_material_; |
| | spec.userdata = &spec_userdata_; |
| | spec.info = &info; |
| | material = nullptr; |
| | userdata = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTendon::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | prefix = m->prefix; |
| | suffix = m->suffix; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTendon::CopyFromSpec() { |
| | *static_cast<mjsTendon*>(this) = spec; |
| | material_ = spec_material_; |
| | userdata_ = spec_userdata_; |
| |
|
| | |
| | for (int i=0; i < path.size(); i++) { |
| | if (path[i]->type == mjWRAP_CYLINDER) { |
| | path[i]->type = mjWRAP_SPHERE; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCTendon::~mjCTendon() { |
| | |
| | for (unsigned int i=0; i < path.size(); i++) { |
| | delete path[i]; |
| | } |
| |
|
| | path.clear(); |
| | } |
| |
|
| |
|
| |
|
| | void mjCTendon::SetModel(mjCModel* _model) { |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | for (int i=0; i < path.size(); i++) { |
| | path[i]->model = _model; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTendon::WrapSite(std::string wrapname, std::string_view wrapinfo) { |
| | |
| | mjCWrap* wrap = new mjCWrap(model, this); |
| | wrap->info = wrapinfo; |
| |
|
| | |
| | wrap->type = mjWRAP_SITE; |
| | wrap->name = wrapname; |
| | wrap->id = (int)path.size(); |
| | path.push_back(wrap); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTendon::WrapGeom(std::string wrapname, std::string sidesite, std::string_view wrapinfo) { |
| | |
| | mjCWrap* wrap = new mjCWrap(model, this); |
| | wrap->info = wrapinfo; |
| |
|
| | |
| | wrap->type = mjWRAP_SPHERE; |
| | wrap->name = wrapname; |
| | wrap->sidesite = sidesite; |
| | wrap->id = (int)path.size(); |
| | path.push_back(wrap); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTendon::WrapJoint(std::string wrapname, double coef, std::string_view wrapinfo) { |
| | |
| | mjCWrap* wrap = new mjCWrap(model, this); |
| | wrap->info = wrapinfo; |
| |
|
| | |
| | wrap->type = mjWRAP_JOINT; |
| | wrap->name = wrapname; |
| | wrap->prm = coef; |
| | wrap->id = (int)path.size(); |
| | path.push_back(wrap); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTendon::WrapPulley(double divisor, std::string_view wrapinfo) { |
| | |
| | mjCWrap* wrap = new mjCWrap(model, this); |
| | wrap->info = wrapinfo; |
| |
|
| | |
| | wrap->type = mjWRAP_PULLEY; |
| | wrap->prm = divisor; |
| | wrap->id = (int)path.size(); |
| | path.push_back(wrap); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjCTendon::NumWraps() const { |
| | return (int)path.size(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | const mjCWrap* mjCTendon::GetWrap(int i) const { |
| | if (i >= 0 && i < (int)path.size()) { |
| | return path[i]; |
| | } |
| | return nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTendon::ResolveReferences(const mjCModel* m) { |
| | int nfailure = 0; |
| | int npulley = 0; |
| | for (int i=0; i < path.size(); i++) { |
| | std::string pname = path[i]->name; |
| | std::string psidesite = path[i]->sidesite; |
| | if (path[i]->type == mjWRAP_PULLEY) { |
| | npulley++; |
| | } |
| | try { |
| | |
| | path[i]->name = prefix + pname + suffix; |
| | path[i]->sidesite = prefix + psidesite + suffix; |
| | path[i]->ResolveReferences(m); |
| | } catch(mjCError) { |
| | |
| | path[i]->name = pname; |
| | path[i]->sidesite = psidesite; |
| | path[i]->ResolveReferences(m); |
| | nfailure++; |
| | } |
| | } |
| | if (nfailure == path.size()-npulley) { |
| | throw mjCError(this, "tendon '%s' (id = %d): no attached reference found", name.c_str(), id); |
| | } |
| | prefix.clear(); |
| | suffix.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTendon::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_tendon) { |
| | throw mjCError(this, "user has more values than nuser_tendon in tendon"); |
| | } |
| | userdata_.resize(model->nuser_tendon); |
| |
|
| | |
| | int sz = (int)path.size(); |
| | if (!sz) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): path cannot be empty", |
| | name.c_str(), id); |
| | } |
| |
|
| | |
| | bool spatial = (path[0]->type != mjWRAP_JOINT); |
| |
|
| | |
| | if (spatial && sz < 2) { |
| | throw mjCError(this, "tendon '%s' (id = %d): spatial path must contain at least two objects", |
| | name.c_str(), id); |
| | } |
| |
|
| | |
| | if (spatial && width <= 0) { |
| | throw mjCError(this, "tendon '%s' (id = %d) must have positive width", name.c_str(), id); |
| | } |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | for (int i=0; i < sz; i++) { |
| | |
| | if (!spatial) { |
| | |
| | if (path[i]->type != mjWRAP_JOINT) { |
| | throw mjCError(this, "tendon '%s' (id = %d): spatial object found in fixed path at pos %d", |
| | name.c_str(), id, i); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | if (armature < 0) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): tendon armature cannot be negative", |
| | name.c_str(), id); |
| | } |
| |
|
| | switch (path[i]->type) { |
| | case mjWRAP_PULLEY: |
| | |
| | if (i > 0 && path[i-1]->type == mjWRAP_PULLEY) { |
| | throw mjCError(this, "tendon '%s' (id = %d): consecutive pulleys (pos %d)", |
| | name.c_str(), id, i); |
| | } |
| |
|
| | |
| | if (i == sz-1) { |
| | throw mjCError(this, "tendon '%s' (id = %d): path ends with pulley", name.c_str(), id); |
| | } |
| | break; |
| |
|
| | case mjWRAP_SITE: |
| | |
| | if ((i == 0 || path[i-1]->type == mjWRAP_PULLEY) && |
| | (i == sz-1 || path[i+1]->type == mjWRAP_PULLEY)) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): site %d needs a neighbor that is not a pulley", |
| | name.c_str(), id, i); |
| | } |
| |
|
| | |
| | if (i < sz-1 && path[i+1]->type == mjWRAP_SITE && path[i]->obj->id == path[i+1]->obj->id) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): site %d is repeated", |
| | name.c_str(), id, i); |
| | } |
| |
|
| | break; |
| |
|
| | case mjWRAP_SPHERE: |
| | case mjWRAP_CYLINDER: |
| | |
| | if (i == 0 || i == sz-1 || path[i-1]->type != mjWRAP_SITE || path[i+1]->type != mjWRAP_SITE) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): geom at pos %d not bracketed by sites", |
| | name.c_str(), id, i); |
| | } |
| |
|
| | if (armature > 0) { |
| | throw mjCError(this, |
| | "tendon '%s' (id = %d): geom wrapping not supported by tendon armature", |
| | name.c_str(), id); |
| | } |
| |
|
| | |
| | model->Geoms()[path[i]->obj->id]->SetNotVisual(); |
| | break; |
| |
|
| | case mjWRAP_JOINT: |
| | throw mjCError(this, |
| | "tendon '%s (id = %d)': joint wrap found in spatial path at pos %d", |
| | name.c_str(), id, i); |
| |
|
| | default: |
| | throw mjCError(this, |
| | "tendon '%s (id = %d)': invalid wrap object at pos %d", |
| | name.c_str(), id, i); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (limited == mjLIMITED_AUTO) { |
| | bool hasrange = !(range[0] == 0 && range[1] == 0); |
| | checklimited(this, compiler->autolimits, "tendon", "", limited, hasrange); |
| | } |
| |
|
| | |
| | if (range[0] >= range[1] && is_limited()) { |
| | throw mjCError(this, "invalid limits in tendon"); |
| | } |
| |
|
| | |
| | if (actfrclimited == mjLIMITED_AUTO) { |
| | bool hasactfrcrange = !(actfrcrange[0] == 0 && actfrcrange[1] == 0); |
| | checklimited(this, compiler->autolimits, "tendon", "", actfrclimited, |
| | hasactfrcrange); |
| | } |
| |
|
| | |
| | if (actfrcrange[0] >= actfrcrange[1] && is_actfrclimited()) { |
| | throw mjCError(this, "invalid actuatorfrcrange in tendon"); |
| | } |
| | if ((actfrcrange[0] > 0 || actfrcrange[1] < 0) && is_actfrclimited()) { |
| | throw mjCError(this, "invalid actuatorfrcrange in tendon"); |
| | } |
| |
|
| | |
| | if (springlength[0] > springlength[1]) { |
| | throw mjCError(this, "invalid springlength in tendon"); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCWrap::mjCWrap(mjCModel* _model, mjCTendon* _tendon) { |
| | elemtype = mjOBJ_UNKNOWN; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | tendon = _tendon; |
| |
|
| | |
| | type = mjWRAP_NONE; |
| | obj = nullptr; |
| | sideid = -1; |
| | prm = 0; |
| | sidesite.clear(); |
| |
|
| | |
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | mjCWrap::mjCWrap(const mjCWrap& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCWrap& mjCWrap::operator=(const mjCWrap& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCWrap_*>(this) = static_cast<const mjCWrap_&>(other); |
| | *static_cast<mjsWrap*>(this) = static_cast<const mjsWrap&>(other); |
| | obj = nullptr; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCWrap::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.info = &info; |
| | } |
| |
|
| |
|
| |
|
| | void mjCWrap::NameSpace(const mjCModel* m) { |
| | name = m->prefix + name + m->suffix; |
| | if (!sidesite.empty()) { |
| | sidesite = m->prefix + sidesite + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCWrap::ResolveReferences(const mjCModel* m) { |
| | mjCBase *pside; |
| |
|
| | |
| | switch (type) { |
| | case mjWRAP_JOINT: |
| | |
| | obj = m->FindObject(mjOBJ_JOINT, name); |
| | if (!obj) { |
| | throw mjCError(this, |
| | "joint '%s' not found in tendon %d, wrap %d", |
| | name.c_str(), tendon->id, id); |
| | } |
| |
|
| | break; |
| |
|
| | case mjWRAP_SPHERE: |
| | |
| | obj = m->FindObject(mjOBJ_GEOM, name); |
| | if (!obj) { |
| | throw mjCError(this, |
| | "geom '%s' not found in tendon %d, wrap %d", |
| | name.c_str(), tendon->id, id); |
| | } |
| |
|
| | |
| | if (((mjCGeom*)obj)->type == mjGEOM_CYLINDER) { |
| | type = mjWRAP_CYLINDER; |
| | } else if (((mjCGeom*)obj)->type != mjGEOM_SPHERE) { |
| | throw mjCError(this, |
| | "geom '%s' in tendon %d, wrap %d is not sphere or cylinder", |
| | name.c_str(), tendon->id, id); |
| | } |
| |
|
| | |
| | if (!sidesite.empty()) { |
| | |
| | pside = m->FindObject(mjOBJ_SITE, sidesite); |
| | if (!pside) { |
| | throw mjCError(this, |
| | "side site '%s' not found in tendon %d, wrap %d", |
| | sidesite.c_str(), tendon->id, id); |
| | } |
| |
|
| | |
| | sideid = pside->id; |
| | } |
| | break; |
| |
|
| | case mjWRAP_PULLEY: |
| | |
| | if (prm < 0) { |
| | throw mjCError(this, |
| | "pulley has negative divisor in tendon %d, wrap %d", |
| | 0, tendon->id, id); |
| | } |
| |
|
| | break; |
| |
|
| | case mjWRAP_SITE: |
| | |
| | obj = m->FindObject(mjOBJ_SITE, name); |
| | if (!obj) { |
| | throw mjCError(this, "site '%s' not found in wrap %d", name.c_str(), id); |
| | } |
| | break; |
| |
|
| | default: |
| | throw mjCError(this, "unknown wrap type in tendon %d, wrap %d", 0, tendon->id, id); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCActuator::mjCActuator(mjCModel* _model, mjCDef* _def) { |
| | mjs_defaultActuator(&spec); |
| | elemtype = mjOBJ_ACTUATOR; |
| |
|
| | |
| | ptarget = nullptr; |
| | spec_target_.clear(); |
| | spec_slidersite_.clear(); |
| | spec_refsite_.clear(); |
| | spec_userdata_.clear(); |
| | trnid[0] = trnid[1] = -1; |
| |
|
| | |
| | if (_def) { |
| | *this = _def->Actuator(); |
| | } |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | classname = _def ? _def->name : "main"; |
| |
|
| | |
| | CopyFromSpec(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | actadr_ = -1; |
| | actdim_ = -1; |
| | } |
| |
|
| |
|
| |
|
| | mjCActuator::mjCActuator(const mjCActuator& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCActuator& mjCActuator::operator=(const mjCActuator& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCActuator_*>(this) = static_cast<const mjCActuator_&>(other); |
| | *static_cast<mjsActuator*>(this) = static_cast<const mjsActuator&>(other); |
| | ptarget = nullptr; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::ForgetKeyframes() { |
| | act_.clear(); |
| | ctrl_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | bool mjCActuator::is_ctrllimited() const { |
| | return islimited(ctrllimited, ctrlrange); |
| | } |
| | bool mjCActuator::is_forcelimited() const { |
| | return islimited(forcelimited, forcerange); |
| | } |
| | bool mjCActuator::is_actlimited() const { |
| | return islimited(actlimited, actrange); |
| | } |
| |
|
| |
|
| |
|
| | std::vector<mjtNum>& mjCActuator::act(const std::string& state_name) { |
| | if (act_.find(state_name) == act_.end()) { |
| | act_[state_name] = std::vector<mjtNum>(model->nu, mjNAN); |
| | } |
| | return act_.at(state_name); |
| | } |
| |
|
| |
|
| |
|
| | mjtNum& mjCActuator::ctrl(const std::string& state_name) { |
| | if (ctrl_.find(state_name) == ctrl_.end()) { |
| | ctrl_[state_name] = mjNAN; |
| | } |
| | return ctrl_.at(state_name); |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.userdata = &spec_userdata_; |
| | spec.target = &spec_target_; |
| | spec.refsite = &spec_refsite_; |
| | spec.slidersite = &spec_slidersite_; |
| | spec.plugin.plugin_name = &plugin_name; |
| | spec.plugin.name = &plugin_instance_name; |
| | spec.info = &info; |
| | userdata = nullptr; |
| | target = nullptr; |
| | refsite = nullptr; |
| | slidersite = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::NameSpace(const mjCModel* m) { |
| | mjCBase::NameSpace(m); |
| | if (!plugin_instance_name.empty()) { |
| | plugin_instance_name = m->prefix + plugin_instance_name + m->suffix; |
| | } |
| | if (!spec_target_.empty()) { |
| | spec_target_ = m->prefix + spec_target_ + m->suffix; |
| | } |
| | if (!spec_refsite_.empty()) { |
| | spec_refsite_ = m->prefix + spec_refsite_ + m->suffix; |
| | } |
| | if (!spec_slidersite_.empty()) { |
| | spec_slidersite_ = m->prefix + spec_slidersite_ + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::CopyFromSpec() { |
| | *static_cast<mjsActuator*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | target_ = spec_target_; |
| | refsite_ = spec_refsite_; |
| | slidersite_ = spec_slidersite_; |
| | plugin.active = spec.plugin.active; |
| | plugin.element = spec.plugin.element; |
| | plugin.plugin_name = spec.plugin.plugin_name; |
| | plugin.name = spec.plugin.name; |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::CopyPlugin() { |
| | model->CopyExplicitPlugin(this); |
| | } |
| |
|
| |
|
| |
|
| | void mjCActuator::ResolveReferences(const mjCModel* m) { |
| | switch (trntype) { |
| | case mjTRN_JOINT: |
| | case mjTRN_JOINTINPARENT: |
| | |
| | ptarget = m->FindObject(mjOBJ_JOINT, target_); |
| | if (!ptarget) { |
| | throw mjCError(this, |
| | "unknown transmission target '%s' for actuator id = %d", target_.c_str(), id); |
| | } |
| | break; |
| |
|
| | case mjTRN_SLIDERCRANK: |
| | |
| | if (slidersite_.empty()) { |
| | throw mjCError(this, "missing base site for slider-crank '%s' (id = %d)", name.c_str(), id); |
| | } |
| | ptarget = m->FindObject(mjOBJ_SITE, slidersite_); |
| | if (!ptarget) { |
| | throw mjCError(this, "base site '%s' not found for actuator %d", slidersite_.c_str(), id); |
| | } |
| | trnid[1] = ptarget->id; |
| |
|
| | |
| | if (cranklength <= 0) { |
| | throw mjCError(this, |
| | "crank length must be positive in actuator '%s' (id = %d)", name.c_str(), id); |
| | } |
| |
|
| | |
| | ptarget = m->FindObject(mjOBJ_SITE, target_); |
| | break; |
| |
|
| | case mjTRN_TENDON: |
| | |
| | ptarget = m->FindObject(mjOBJ_TENDON, target_); |
| | break; |
| |
|
| | case mjTRN_SITE: |
| | |
| | if (!refsite_.empty()) { |
| | ptarget = m->FindObject(mjOBJ_SITE, refsite_); |
| | if (!ptarget) { |
| | throw mjCError(this, "reference site '%s' not found for actuator %d", refsite_.c_str(), id); |
| | } |
| | trnid[1] = ptarget->id; |
| | } |
| |
|
| | |
| | ptarget = m->FindObject(mjOBJ_SITE, target_); |
| | break; |
| |
|
| | case mjTRN_BODY: |
| | |
| | ptarget = m->FindObject(mjOBJ_BODY, target_); |
| | break; |
| |
|
| | default: |
| | throw mjCError(this, "invalid transmission type in actuator"); |
| | } |
| |
|
| | |
| | if (!ptarget) { |
| | throw mjCError(this, "transmission target '%s' not found in actuator %d", target_.c_str(), id); |
| | } else { |
| | trnid[0] = ptarget->id; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCActuator::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_actuator) { |
| | throw mjCError(this, "user has more values than nuser_actuator in actuator '%s' (id = %d)", |
| | name.c_str(), id); |
| | } |
| | userdata_.resize(model->nuser_actuator); |
| |
|
| | |
| | if (target_.empty()) { |
| | throw mjCError(this, |
| | "missing transmission target for actuator"); |
| | } |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | if (gaintype == mjGAIN_FIXED && biastype == mjBIAS_AFFINE && |
| | gainprm[0] == -biasprm[1] && inheritrange > 0) { |
| | |
| | double* range; |
| | if (dyntype == mjDYN_NONE || dyntype == mjDYN_FILTEREXACT) { |
| | |
| | range = ctrlrange; |
| | } else if (dyntype == mjDYN_INTEGRATOR) { |
| | |
| | range = actrange; |
| | } else { |
| | throw mjCError(this, "inheritrange only available for position " |
| | "and intvelocity actuators"); |
| | } |
| |
|
| | const double* target_range; |
| | if (trntype == mjTRN_JOINT) { |
| | mjCJoint* pjnt = (mjCJoint*) ptarget; |
| | if (pjnt->spec.type != mjJNT_HINGE && pjnt->spec.type != mjJNT_SLIDE) { |
| | throw mjCError(this, "inheritrange can only be used with hinge and slide joints, " |
| | "actuator"); |
| | } |
| | target_range = pjnt->get_range(); |
| | } else if (trntype == mjTRN_TENDON) { |
| | mjCTendon* pten = (mjCTendon*) ptarget; |
| | target_range = pten->get_range(); |
| | } else { |
| | throw mjCError(this, "inheritrange can only be used with joint and tendon transmission, " |
| | "actuator"); |
| | } |
| |
|
| | if (target_range[0] == target_range[1]) { |
| | throw mjCError(this, "inheritrange used but target '%s' has no range defined in actuator %d", |
| | target_.c_str(), id); |
| | } |
| |
|
| | |
| | double mean = 0.5*(target_range[1] + target_range[0]); |
| | double radius = 0.5*(target_range[1] - target_range[0]) * inheritrange; |
| | range[0] = mean - radius; |
| | range[1] = mean + radius; |
| | } |
| |
|
| | |
| | if (forcelimited == mjLIMITED_AUTO) { |
| | bool hasrange = !(forcerange[0] == 0 && forcerange[1] == 0); |
| | checklimited(this, compiler->autolimits, "actuator", "force", forcelimited, hasrange); |
| | } |
| | if (ctrllimited == mjLIMITED_AUTO) { |
| | bool hasrange = !(ctrlrange[0] == 0 && ctrlrange[1] == 0); |
| | checklimited(this, compiler->autolimits, "actuator", "ctrl", ctrllimited, hasrange); |
| | } |
| | if (actlimited == mjLIMITED_AUTO) { |
| | bool hasrange = !(actrange[0] == 0 && actrange[1] == 0); |
| | checklimited(this, compiler->autolimits, "actuator", "act", actlimited, hasrange); |
| | } |
| |
|
| | |
| | if (forcerange[0] >= forcerange[1] && is_forcelimited()) { |
| | throw mjCError(this, "invalid force range for actuator"); |
| | } |
| | if (ctrlrange[0] >= ctrlrange[1] && is_ctrllimited()) { |
| | throw mjCError(this, "invalid control range for actuator"); |
| | } |
| | if (actrange[0] >= actrange[1] && is_actlimited()) { |
| | throw mjCError(this, "invalid actrange for actuator"); |
| | } |
| | if (is_actlimited() && dyntype == mjDYN_NONE) { |
| | throw mjCError(this, "actrange specified but dyntype is 'none' in actuator"); |
| | } |
| |
|
| | |
| | if (!plugin.active) { |
| | if (actdim > 1 && dyntype != mjDYN_USER) { |
| | throw mjCError(this, "actdim > 1 is only allowed for dyntype 'user' in actuator"); |
| | } |
| | if (actdim == 1 && dyntype == mjDYN_NONE) { |
| | throw mjCError(this, "invalid actdim 1 in stateless actuator"); |
| | } |
| | if (actdim == 0 && dyntype != mjDYN_NONE) { |
| | throw mjCError(this, "invalid actdim 0 in stateful actuator"); |
| | } |
| | } |
| |
|
| | |
| | if (actdim < 0) { |
| | actdim = (dyntype != mjDYN_NONE); |
| | } |
| |
|
| | |
| | for (int i=0; i < 2; i++) { |
| | |
| | double* prm = NULL; |
| | if (i == 0 && gaintype == mjGAIN_MUSCLE) { |
| | prm = gainprm; |
| | } else if (i == 1 && biastype == mjBIAS_MUSCLE) { |
| | prm = biasprm; |
| | } |
| |
|
| | |
| | if (!prm) { |
| | continue; |
| | } |
| |
|
| | |
| | if (prm[0] >= prm[1]) { |
| | throw mjCError(this, "range[0]<range[1] required in muscle"); |
| | } |
| |
|
| | |
| | if (prm[4] >= 1 || prm[5] <= 1) { |
| | throw mjCError(this, "lmin<1<lmax required in muscle"); |
| | } |
| |
|
| | |
| | if (prm[3] <= 0 || prm[6] <= 0 || prm[7] <= 0 || prm[8] <= 0) { |
| | throw mjCError(this, |
| | "positive scale, vmax, fpmax, fvmax required in muscle '%s' (id = %d)", |
| | name.c_str(), id); |
| | } |
| | } |
| |
|
| | |
| | if (plugin.active) { |
| | if (plugin_name.empty() && plugin_instance_name.empty()) { |
| | throw mjCError( |
| | this, "neither 'plugin' nor 'instance' is specified for actuator '%s', (id = %d)", |
| | name.c_str(), id); |
| | } |
| |
|
| | mjCPlugin* plugin_instance = static_cast<mjCPlugin*>(plugin.element); |
| | model->ResolvePlugin(this, plugin_name, plugin_instance_name, &plugin_instance); |
| | plugin.element = plugin_instance; |
| | const mjpPlugin* pplugin = mjp_getPluginAtSlot(plugin_instance->plugin_slot); |
| | if (!(pplugin->capabilityflags & mjPLUGIN_ACTUATOR)) { |
| | throw mjCError(this, "plugin '%s' does not support actuators", pplugin->name); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCSensor::mjCSensor(mjCModel* _model) { |
| | mjs_defaultSensor(&spec); |
| | elemtype = mjOBJ_SENSOR; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_objname_.clear(); |
| | spec_refname_.clear(); |
| | spec_userdata_.clear(); |
| | obj = nullptr; |
| | ref = nullptr; |
| |
|
| | |
| | CopyFromSpec(); |
| |
|
| | |
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | mjCSensor::mjCSensor(const mjCSensor& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCSensor& mjCSensor::operator=(const mjCSensor& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCSensor_*>(this) = static_cast<const mjCSensor_&>(other); |
| | *static_cast<mjsSensor*>(this) = static_cast<const mjsSensor&>(other); |
| | obj = nullptr; |
| | ref = nullptr; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSensor::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.userdata = &spec_userdata_; |
| | spec.objname = &spec_objname_; |
| | spec.refname = &spec_refname_; |
| | spec.plugin.plugin_name = &plugin_name; |
| | spec.plugin.name = &plugin_instance_name; |
| | spec.info = &info; |
| | userdata = nullptr; |
| | objname = nullptr; |
| | refname = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSensor::NameSpace(const mjCModel* m) { |
| | if (!name.empty()) { |
| | name = m->prefix + name + m->suffix; |
| | } |
| | if (!plugin_instance_name.empty()) { |
| | plugin_instance_name = m->prefix + plugin_instance_name + m->suffix; |
| | } |
| | prefix = m->prefix; |
| | suffix = m->suffix; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSensor::CopyFromSpec() { |
| | *static_cast<mjsSensor*>(this) = spec; |
| | userdata_ = spec_userdata_; |
| | objname_ = spec_objname_; |
| | refname_ = spec_refname_; |
| | plugin.active = spec.plugin.active; |
| | plugin.element = spec.plugin.element; |
| | plugin.plugin_name = spec.plugin.plugin_name; |
| | plugin.name = spec.plugin.name; |
| | } |
| |
|
| |
|
| |
|
| | void mjCSensor::CopyPlugin() { |
| | model->CopyExplicitPlugin(this); |
| | } |
| |
|
| |
|
| |
|
| | void mjCSensor::ResolveReferences(const mjCModel* m) { |
| | obj = nullptr; |
| | ref = nullptr; |
| | objname_ = prefix + objname_ + suffix; |
| | refname_ = prefix + refname_ + suffix; |
| |
|
| | |
| | if (objtype != mjOBJ_UNKNOWN) { |
| | obj = m->FindObject(objtype, objname_); |
| | } |
| | if (reftype != mjOBJ_UNKNOWN) { |
| | ref = m->FindObject(reftype, refname_); |
| | } |
| |
|
| | |
| | if (objtype != mjOBJ_UNKNOWN && reftype != mjOBJ_UNKNOWN && !obj && ref) { |
| | objname_ = spec_objname_; |
| | obj = m->FindObject(objtype, objname_); |
| | } |
| | if (objtype != mjOBJ_UNKNOWN && reftype != mjOBJ_UNKNOWN && obj && !ref) { |
| | refname_ = spec_refname_; |
| | ref = m->FindObject(reftype, refname_); |
| | } |
| |
|
| | |
| | if (objtype != mjOBJ_UNKNOWN) { |
| | |
| | if (objname_.empty()) { |
| | throw mjCError(this, "missing name of sensorized object in sensor"); |
| | } |
| |
|
| | |
| | if (!obj) { |
| | throw mjCError(this, "unrecognized name '%s' of sensorized object", objname_.c_str()); |
| | } |
| |
|
| | |
| | if (objtype == mjOBJ_GEOM) { |
| | ((mjCGeom*)obj)->SetNotVisual(); |
| | } |
| |
|
| | } else if (type != mjSENS_E_POTENTIAL && |
| | type != mjSENS_E_KINETIC && |
| | type != mjSENS_CLOCK && |
| | type != mjSENS_PLUGIN && |
| | type != mjSENS_USER) { |
| | throw mjCError(this, "invalid type in sensor"); |
| | } |
| |
|
| | |
| | if (reftype != mjOBJ_UNKNOWN) { |
| | |
| | if (refname_.empty()) { |
| | throw mjCError(this, "missing name of reference frame object in sensor"); |
| | } |
| |
|
| | |
| | if (!ref) { |
| | throw mjCError(this, "unrecognized name '%s' of object", refname_.c_str()); |
| | } |
| |
|
| | |
| | if (reftype != mjOBJ_BODY && reftype != mjOBJ_XBODY && |
| | reftype != mjOBJ_GEOM && reftype != mjOBJ_SITE && reftype != mjOBJ_CAMERA) { |
| | throw mjCError(this, |
| | "reference frame object must be (x)body, geom, site or camera in sensor"); |
| | } |
| | } |
| |
|
| | spec_objname_ = objname_; |
| | spec_refname_ = refname_; |
| | prefix.clear(); |
| | suffix.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCSensor::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (userdata_.size() > model->nuser_sensor) { |
| | throw mjCError(this, "user has more values than nuser_sensor in sensor"); |
| | } |
| | userdata_.resize(model->nuser_sensor); |
| |
|
| | |
| | if (noise < 0) { |
| | throw mjCError(this, "negative noise in sensor"); |
| | } |
| |
|
| | |
| | if (cutoff < 0) { |
| | throw mjCError(this, "negative cutoff in sensor"); |
| | } |
| |
|
| | |
| | ResolveReferences(model); |
| |
|
| | |
| | switch (type) { |
| | case mjSENS_TOUCH: |
| | case mjSENS_ACCELEROMETER: |
| | case mjSENS_VELOCIMETER: |
| | case mjSENS_GYRO: |
| | case mjSENS_FORCE: |
| | case mjSENS_TORQUE: |
| | case mjSENS_MAGNETOMETER: |
| | case mjSENS_RANGEFINDER: |
| | case mjSENS_CAMPROJECTION: |
| | |
| | if (objtype != mjOBJ_SITE) { |
| | throw mjCError(this, "sensor must be attached to site"); |
| | } |
| |
|
| | |
| | if (type == mjSENS_TOUCH || type == mjSENS_RANGEFINDER) { |
| | dim = 1; |
| | datatype = mjDATATYPE_POSITIVE; |
| | } else if (type == mjSENS_CAMPROJECTION) { |
| | dim = 2; |
| | datatype = mjDATATYPE_REAL; |
| | } else { |
| | dim = 3; |
| | datatype = mjDATATYPE_REAL; |
| | } |
| |
|
| | |
| | if (type == mjSENS_MAGNETOMETER || type == mjSENS_RANGEFINDER || type == mjSENS_CAMPROJECTION) { |
| | needstage = mjSTAGE_POS; |
| | } else if (type == mjSENS_GYRO || type == mjSENS_VELOCIMETER) { |
| | needstage = mjSTAGE_VEL; |
| | } else { |
| | needstage = mjSTAGE_ACC; |
| | } |
| |
|
| | |
| | if (type == mjSENS_CAMPROJECTION) { |
| | mjCCamera* camref = (mjCCamera*)ref; |
| | if (!camref->resolution[0] || !camref->resolution[1]) { |
| | throw mjCError(this, "camera projection sensor requires camera resolution"); |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_JOINTPOS: |
| | case mjSENS_JOINTVEL: |
| | case mjSENS_JOINTACTFRC: |
| | |
| | if (objtype != mjOBJ_JOINT) { |
| | throw mjCError(this, "sensor must be attached to joint"); |
| | } |
| |
|
| | |
| | if (((mjCJoint*)obj)->type != mjJNT_SLIDE && ((mjCJoint*)obj)->type != mjJNT_HINGE) { |
| | throw mjCError(this, "joint must be slide or hinge in sensor"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_JOINTPOS) { |
| | needstage = mjSTAGE_POS; |
| | } else if (type == mjSENS_JOINTVEL) { |
| | needstage = mjSTAGE_VEL; |
| | } else if (type == mjSENS_JOINTACTFRC) { |
| | needstage = mjSTAGE_ACC; |
| | } |
| | break; |
| |
|
| | case mjSENS_TENDONACTFRC: |
| | |
| | if (objtype != mjOBJ_TENDON) { |
| | throw mjCError(this, "sensor must be attached to tendon"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | needstage = mjSTAGE_ACC; |
| | break; |
| |
|
| | case mjSENS_TENDONPOS: |
| | case mjSENS_TENDONVEL: |
| | |
| | if (objtype != mjOBJ_TENDON) { |
| | throw mjCError(this, "sensor must be attached to tendon"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_TENDONPOS) { |
| | needstage = mjSTAGE_POS; |
| | } else { |
| | needstage = mjSTAGE_VEL; |
| | } |
| | break; |
| |
|
| | case mjSENS_ACTUATORPOS: |
| | case mjSENS_ACTUATORVEL: |
| | case mjSENS_ACTUATORFRC: |
| | |
| | if (objtype != mjOBJ_ACTUATOR) { |
| | throw mjCError(this, "sensor must be attached to actuator"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_ACTUATORPOS) { |
| | needstage = mjSTAGE_POS; |
| | } else if (type == mjSENS_ACTUATORVEL) { |
| | needstage = mjSTAGE_VEL; |
| | } else { |
| | needstage = mjSTAGE_ACC; |
| | } |
| | break; |
| |
|
| | case mjSENS_BALLQUAT: |
| | case mjSENS_BALLANGVEL: |
| | |
| | if (objtype != mjOBJ_JOINT) { |
| | throw mjCError(this, "sensor must be attached to joint"); |
| | } |
| |
|
| | |
| | if (((mjCJoint*)obj)->type != mjJNT_BALL) { |
| | throw mjCError(this, "joint must be ball in sensor"); |
| | } |
| |
|
| | |
| | if (type == mjSENS_BALLQUAT) { |
| | dim = 4; |
| | datatype = mjDATATYPE_QUATERNION; |
| | needstage = mjSTAGE_POS; |
| | } else { |
| | dim = 3; |
| | datatype = mjDATATYPE_REAL; |
| | needstage = mjSTAGE_VEL; |
| | } |
| | break; |
| |
|
| | case mjSENS_JOINTLIMITPOS: |
| | case mjSENS_JOINTLIMITVEL: |
| | case mjSENS_JOINTLIMITFRC: |
| | |
| | if (objtype != mjOBJ_JOINT) { |
| | throw mjCError(this, "sensor must be attached to joint"); |
| | } |
| |
|
| | |
| | if (!((mjCJoint*)obj)->is_limited()) { |
| | throw mjCError(this, "joint must be limited in sensor"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_JOINTLIMITPOS) { |
| | needstage = mjSTAGE_POS; |
| | } else if (type == mjSENS_JOINTLIMITVEL) { |
| | needstage = mjSTAGE_VEL; |
| | } else { |
| | needstage = mjSTAGE_ACC; |
| | } |
| | break; |
| |
|
| | case mjSENS_TENDONLIMITPOS: |
| | case mjSENS_TENDONLIMITVEL: |
| | case mjSENS_TENDONLIMITFRC: |
| | |
| | if (objtype != mjOBJ_TENDON) { |
| | throw mjCError(this, "sensor must be attached to tendon"); |
| | } |
| |
|
| | |
| | if (!((mjCTendon*)obj)->is_limited()) { |
| | throw mjCError(this, "tendon must be limited in sensor"); |
| | } |
| |
|
| | |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_TENDONLIMITPOS) { |
| | needstage = mjSTAGE_POS; |
| | } else if (type == mjSENS_TENDONLIMITVEL) { |
| | needstage = mjSTAGE_VEL; |
| | } else { |
| | needstage = mjSTAGE_ACC; |
| | } |
| | break; |
| |
|
| | case mjSENS_FRAMEPOS: |
| | case mjSENS_FRAMEQUAT: |
| | case mjSENS_FRAMEXAXIS: |
| | case mjSENS_FRAMEYAXIS: |
| | case mjSENS_FRAMEZAXIS: |
| | case mjSENS_FRAMELINVEL: |
| | case mjSENS_FRAMEANGVEL: |
| | case mjSENS_FRAMELINACC: |
| | case mjSENS_FRAMEANGACC: |
| | |
| | if (objtype != mjOBJ_BODY && objtype != mjOBJ_XBODY && |
| | objtype != mjOBJ_GEOM && objtype != mjOBJ_SITE && objtype != mjOBJ_CAMERA) { |
| | throw mjCError(this, "sensor must be attached to (x)body, geom, site or camera"); |
| | } |
| |
|
| | |
| | if (type == mjSENS_FRAMEQUAT) { |
| | dim = 4; |
| | } else { |
| | dim = 3; |
| | } |
| |
|
| | |
| | if (type == mjSENS_FRAMEQUAT) { |
| | datatype = mjDATATYPE_QUATERNION; |
| | } else if (type == mjSENS_FRAMEXAXIS || |
| | type == mjSENS_FRAMEYAXIS || |
| | type == mjSENS_FRAMEZAXIS) { |
| | datatype = mjDATATYPE_AXIS; |
| | } else { |
| | datatype = mjDATATYPE_REAL; |
| | } |
| |
|
| | |
| | if (type == mjSENS_FRAMELINACC || type == mjSENS_FRAMEANGACC) { |
| | needstage = mjSTAGE_ACC; |
| | } else if (type == mjSENS_FRAMELINVEL || type == mjSENS_FRAMEANGVEL) { |
| | needstage = mjSTAGE_VEL; |
| | } else { |
| | needstage = mjSTAGE_POS; |
| | } |
| | break; |
| |
|
| | case mjSENS_SUBTREECOM: |
| | case mjSENS_SUBTREELINVEL: |
| | case mjSENS_SUBTREEANGMOM: |
| | |
| | if (objtype != mjOBJ_BODY) { |
| | throw mjCError(this, "sensor must be attached to body"); |
| | } |
| |
|
| | |
| | dim = 3; |
| | datatype = mjDATATYPE_REAL; |
| | if (type == mjSENS_SUBTREECOM) { |
| | needstage = mjSTAGE_POS; |
| | } else { |
| | needstage = mjSTAGE_VEL; |
| | } |
| | break; |
| |
|
| | case mjSENS_INSIDESITE: |
| | if (objtype != mjOBJ_BODY && objtype != mjOBJ_XBODY && |
| | objtype != mjOBJ_GEOM && objtype != mjOBJ_SITE && objtype != mjOBJ_CAMERA) { |
| | throw mjCError(this, "sensor must be attached to (x)body, geom, site or camera"); |
| | } |
| | if (reftype != mjOBJ_SITE) { |
| | throw mjCError(this, "sensor must be associated with a site"); |
| | } |
| | dim = 1; |
| | datatype = mjDATATYPE_REAL; |
| | needstage = mjSTAGE_POS; |
| | break; |
| |
|
| | case mjSENS_GEOMDIST: |
| | case mjSENS_GEOMNORMAL: |
| | case mjSENS_GEOMFROMTO: |
| | |
| | if ((objtype != mjOBJ_BODY && objtype != mjOBJ_GEOM) || |
| | (reftype != mjOBJ_BODY && reftype != mjOBJ_GEOM)) { |
| | throw mjCError(this, "sensor must be attached to body or geom"); |
| | } |
| |
|
| | |
| | if (objtype == reftype && obj == ref) { |
| | throw mjCError(this, "1st body/geom must be different from 2nd body/geom"); |
| | } |
| |
|
| | |
| | if ((objtype == mjOBJ_GEOM && static_cast<mjCGeom*>(obj)->Type() == mjGEOM_HFIELD) || |
| | (reftype == mjOBJ_GEOM && static_cast<mjCGeom*>(ref)->Type() == mjGEOM_HFIELD)) { |
| | throw mjCError(this, "height fields are not supported in geom distance sensors"); |
| | } |
| |
|
| | |
| | needstage = mjSTAGE_POS; |
| | if (type == mjSENS_GEOMDIST) { |
| | dim = 1; |
| | datatype = mjDATATYPE_POSITIVE; |
| | } else if (type == mjSENS_GEOMNORMAL) { |
| | dim = 3; |
| | datatype = mjDATATYPE_AXIS; |
| | } else { |
| | dim = 6; |
| | datatype = mjDATATYPE_REAL; |
| | } |
| | break; |
| |
|
| | case mjSENS_E_POTENTIAL: |
| | case mjSENS_E_KINETIC: |
| | case mjSENS_CLOCK: |
| | dim = 1; |
| | needstage = mjSTAGE_POS; |
| | datatype = mjDATATYPE_REAL; |
| | break; |
| |
|
| | case mjSENS_USER: |
| | |
| | if (dim < 0) { |
| | throw mjCError(this, "sensor dim must be positive in sensor"); |
| | } |
| |
|
| | |
| | if (datatype == mjDATATYPE_AXIS && dim != 3) { |
| | throw mjCError(this, |
| | "datatype AXIS requires dim=3 in sensor"); |
| | } |
| | if (datatype == mjDATATYPE_QUATERNION && dim != 4) { |
| | throw mjCError(this, "datatype QUATERNION requires dim=4 in sensor"); |
| | } |
| | break; |
| |
|
| | case mjSENS_PLUGIN: |
| | dim = 0; |
| | datatype = mjDATATYPE_REAL; |
| |
|
| | if (plugin_name.empty() && plugin_instance_name.empty()) { |
| | throw mjCError(this, "neither 'plugin' nor 'instance' is specified for sensor"); |
| | } |
| |
|
| | |
| | { |
| | mjCPlugin* plugin_instance = static_cast<mjCPlugin*>(plugin.element); |
| | model->ResolvePlugin(this, plugin_name, plugin_instance_name, &plugin_instance); |
| | plugin.element = plugin_instance; |
| | const mjpPlugin* pplugin = mjp_getPluginAtSlot(plugin_instance->plugin_slot); |
| | if (!(pplugin->capabilityflags & mjPLUGIN_SENSOR)) { |
| | throw mjCError(this, "plugin '%s' does not support sensors", pplugin->name); |
| | } |
| | needstage = static_cast<mjtStage>(pplugin->needstage); |
| | } |
| |
|
| | break; |
| |
|
| | default: |
| | throw mjCError(this, "invalid type in sensor '%s' (id = %d)", name.c_str(), id); |
| | } |
| |
|
| | |
| | if (cutoff > 0 && (datatype == mjDATATYPE_QUATERNION || |
| | (datatype == mjDATATYPE_AXIS && type != mjSENS_GEOMNORMAL))) { |
| | throw mjCError(this, "cutoff applied to axis or quaternion datatype in sensor"); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCNumeric::mjCNumeric(mjCModel* _model) { |
| | mjs_defaultNumeric(&spec); |
| | elemtype = mjOBJ_NUMERIC; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_data_.clear(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCNumeric::mjCNumeric(const mjCNumeric& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCNumeric& mjCNumeric::operator=(const mjCNumeric& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCNumeric_*>(this) = static_cast<const mjCNumeric_&>(other); |
| | *static_cast<mjsNumeric*>(this) = static_cast<const mjsNumeric&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCNumeric::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.data = &spec_data_; |
| | spec.info = &info; |
| | data = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCNumeric::CopyFromSpec() { |
| | *static_cast<mjsNumeric*>(this) = spec; |
| | data_ = spec_data_; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCNumeric::~mjCNumeric() { |
| | spec_data_.clear(); |
| | data_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCNumeric::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (size && !data_.empty() && size < (int)data_.size()) { |
| | throw mjCError(this, |
| | "numeric '%s' (id = %d): specified size smaller than initialization array", |
| | name.c_str(), id); |
| | } |
| |
|
| | |
| | if (!size) { |
| | size = (int)data_.size(); |
| | } |
| |
|
| | |
| | if (!size) { |
| | throw mjCError(this, "numeric '%s' (id = %d): size cannot be zero", name.c_str(), id); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCText::mjCText(mjCModel* _model) { |
| | mjs_defaultText(&spec); |
| | elemtype = mjOBJ_TEXT; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_data_.clear(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCText::mjCText(const mjCText& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCText& mjCText::operator=(const mjCText& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCText_*>(this) = static_cast<const mjCText_&>(other); |
| | *static_cast<mjsText*>(this) = static_cast<const mjsText&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCText::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.data = &spec_data_; |
| | spec.info = &info; |
| | data = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCText::CopyFromSpec() { |
| | *static_cast<mjsText*>(this) = spec; |
| | data_ = spec_data_; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCText::~mjCText() { |
| | data_.clear(); |
| | spec_data_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCText::Compile(void) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (data_.empty()) { |
| | throw mjCError(this, "text '%s' (id = %d): size cannot be zero", name.c_str(), id); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCTuple::mjCTuple(mjCModel* _model) { |
| | mjs_defaultTuple(&spec); |
| | elemtype = mjOBJ_TUPLE; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_objtype_.clear(); |
| | spec_objname_.clear(); |
| | spec_objprm_.clear(); |
| | obj.clear(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCTuple::mjCTuple(const mjCTuple& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCTuple& mjCTuple::operator=(const mjCTuple& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCTuple_*>(this) = static_cast<const mjCTuple_&>(other); |
| | *static_cast<mjsTuple*>(this) = static_cast<const mjsTuple&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTuple::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.objtype = (mjIntVec*)&spec_objtype_; |
| | spec.objname = &spec_objname_; |
| | spec.objprm = &spec_objprm_; |
| | spec.info = &info; |
| | objname = nullptr; |
| | objprm = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCTuple::NameSpace(const mjCModel* m) { |
| | if (!name.empty()) { |
| | name = m->prefix + name + m->suffix; |
| | } |
| | for (int i=0; i < spec_objname_.size(); i++) { |
| | spec_objname_[i] = m->prefix + spec_objname_[i] + m->suffix; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | void mjCTuple::CopyFromSpec() { |
| | *static_cast<mjsTuple*>(this) = spec; |
| | objtype_ = spec_objtype_; |
| | objname_ = spec_objname_; |
| | objprm_ = spec_objprm_; |
| | objtype = (mjIntVec*)&objtype_; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCTuple::~mjCTuple() { |
| | objtype_.clear(); |
| | objname_.clear(); |
| | objprm_.clear(); |
| | spec_objtype_.clear(); |
| | spec_objname_.clear(); |
| | spec_objprm_.clear(); |
| | obj.clear(); |
| | } |
| |
|
| |
|
| |
|
| | void mjCTuple::ResolveReferences(const mjCModel* m) { |
| | |
| | if (objtype_.empty()) { |
| | throw mjCError(this, "tuple '%s' (id = %d) is empty", name.c_str(), id); |
| | } |
| |
|
| | |
| | if (objtype_.size() != objname_.size() || objtype_.size() != objprm_.size()) { |
| | throw mjCError(this, |
| | "tuple '%s' (id = %d) has object arrays with different sizes", name.c_str(), id); |
| | } |
| |
|
| | |
| | obj.resize(objtype_.size()); |
| |
|
| | |
| | for (int i=0; i < objtype_.size(); i++) { |
| | |
| | mjCBase* res = m->FindObject(objtype_[i], objname_[i]); |
| | if (!res) { |
| | throw mjCError(this, "unrecognized object '%s' in tuple %d", objname_[i].c_str(), id); |
| | } |
| |
|
| | |
| | if (objtype_[i] == mjOBJ_GEOM) { |
| | ((mjCGeom*)res)->SetNotVisual(); |
| | } |
| |
|
| | |
| | obj[i] = res; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCTuple::Compile(void) { |
| | CopyFromSpec(); |
| | ResolveReferences(model); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | mjCKey::mjCKey(mjCModel* _model) { |
| | mjs_defaultKey(&spec); |
| | elemtype = mjOBJ_KEY; |
| |
|
| | |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| |
|
| | |
| | spec_qpos_.clear(); |
| | spec_qvel_.clear(); |
| | spec_act_.clear(); |
| | spec_mpos_.clear(); |
| | spec_mquat_.clear(); |
| | spec_ctrl_.clear(); |
| |
|
| | |
| | PointToLocal(); |
| |
|
| | |
| | CopyFromSpec(); |
| | } |
| |
|
| |
|
| |
|
| | mjCKey::mjCKey(const mjCKey& other) { |
| | *this = other; |
| | } |
| |
|
| |
|
| |
|
| | mjCKey& mjCKey::operator=(const mjCKey& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCKey_*>(this) = static_cast<const mjCKey_&>(other); |
| | *static_cast<mjsKey*>(this) = static_cast<const mjsKey&>(other); |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCKey::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.qpos = &spec_qpos_; |
| | spec.qvel = &spec_qvel_; |
| | spec.act = &spec_act_; |
| | spec.mpos = &spec_mpos_; |
| | spec.mquat = &spec_mquat_; |
| | spec.ctrl = &spec_ctrl_; |
| | spec.info = &info; |
| | qpos = nullptr; |
| | qvel = nullptr; |
| | act = nullptr; |
| | mpos = nullptr; |
| | mquat = nullptr; |
| | ctrl = nullptr; |
| | } |
| |
|
| |
|
| |
|
| | void mjCKey::CopyFromSpec() { |
| | *static_cast<mjsKey*>(this) = spec; |
| | qpos_ = spec_qpos_; |
| | qvel_ = spec_qvel_; |
| | act_ = spec_act_; |
| | mpos_ = spec_mpos_; |
| | mquat_ = spec_mquat_; |
| | ctrl_ = spec_ctrl_; |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjCKey::~mjCKey() { |
| | qpos_.clear(); |
| | qvel_.clear(); |
| | act_.clear(); |
| | mpos_.clear(); |
| | mquat_.clear(); |
| | ctrl_.clear(); |
| | spec_qpos_.clear(); |
| | spec_qvel_.clear(); |
| | spec_act_.clear(); |
| | spec_mpos_.clear(); |
| | spec_mquat_.clear(); |
| | spec_ctrl_.clear(); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCKey::Compile(const mjModel* m) { |
| | CopyFromSpec(); |
| |
|
| | |
| | if (qpos_.empty()) { |
| | qpos_.resize(m->nq); |
| | for (int i=0; i < m->nq; i++) { |
| | qpos_[i] = (double)m->qpos0[i]; |
| | } |
| | } else if (qpos_.size() != m->nq) { |
| | throw mjCError(this, "keyframe %d: invalid qpos size, expected length %d", nullptr, id, m->nq); |
| | } |
| |
|
| | |
| | if (qvel_.empty()) { |
| | qvel_.resize(m->nv); |
| | for (int i=0; i < m->nv; i++) { |
| | qvel_[i] = 0; |
| | } |
| | } else if (qvel_.size() != m->nv) { |
| | throw mjCError(this, "keyframe %d: invalid qvel size, expected length %d", nullptr, id, m->nv); |
| | } |
| |
|
| | |
| | if (act_.empty()) { |
| | act_.resize(m->na); |
| | for (int i=0; i < m->na; i++) { |
| | act_[i] = 0; |
| | } |
| | } else if (act_.size() != m->na) { |
| | throw mjCError(this, "keyframe %d: invalid act size, expected length %d", nullptr, id, m->na); |
| | } |
| |
|
| | |
| | if (mpos_.empty()) { |
| | mpos_.resize(3*m->nmocap); |
| | if (m->nmocap) { |
| | for (int i=0; i < m->nbody; i++) { |
| | if (m->body_mocapid[i] >= 0) { |
| | int mocapid = m->body_mocapid[i]; |
| | mpos_[3*mocapid] = m->body_pos[3*i]; |
| | mpos_[3*mocapid+1] = m->body_pos[3*i+1]; |
| | mpos_[3*mocapid+2] = m->body_pos[3*i+2]; |
| | } |
| | } |
| | } |
| | } else if (mpos_.size() != 3*m->nmocap) { |
| | throw mjCError(this, "keyframe %d: invalid mpos size, expected length %d", nullptr, id, 3*m->nmocap); |
| | } |
| |
|
| | |
| | if (mquat_.empty()) { |
| | mquat_.resize(4*m->nmocap); |
| | if (m->nmocap) { |
| | for (int i=0; i < m->nbody; i++) { |
| | if (m->body_mocapid[i] >= 0) { |
| | int mocapid = m->body_mocapid[i]; |
| | mquat_[4*mocapid] = m->body_quat[4*i]; |
| | mquat_[4*mocapid+1] = m->body_quat[4*i+1]; |
| | mquat_[4*mocapid+2] = m->body_quat[4*i+2]; |
| | mquat_[4*mocapid+3] = m->body_quat[4*i+3]; |
| | } |
| | } |
| | } |
| | } else if (mquat_.size() != 4*m->nmocap) { |
| | throw mjCError(this, "keyframe %d: invalid mquat size, expected length %d", nullptr, id, 4*m->nmocap); |
| | } |
| |
|
| | |
| | if (ctrl_.empty()) { |
| | ctrl_.resize(m->nu); |
| | for (int i=0; i < m->nu; i++) { |
| | ctrl_[i] = 0; |
| | } |
| | } else if (ctrl_.size() != m->nu) { |
| | throw mjCError(this, "keyframe %d: invalid ctrl size, expected length %d", nullptr, id, m->nu); |
| | } |
| | } |
| |
|
| |
|
| | |
| |
|
| | |
| | mjCPlugin::mjCPlugin(mjCModel* _model) { |
| | name = ""; |
| | nstate = -1; |
| | plugin_slot = -1; |
| | parent = this; |
| | model = _model; |
| | if (_model) compiler = &_model->spec.compiler; |
| | name.clear(); |
| | plugin_name.clear(); |
| |
|
| | |
| | mjs_defaultPlugin(&spec); |
| | elemtype = mjOBJ_PLUGIN; |
| | spec.plugin_name = &plugin_name; |
| | spec.info = &info; |
| |
|
| | PointToLocal(); |
| | } |
| |
|
| |
|
| |
|
| | mjCPlugin::mjCPlugin(const mjCPlugin& other) { |
| | *this = other; |
| | id = -1; |
| | } |
| |
|
| |
|
| |
|
| | mjCPlugin& mjCPlugin::operator=(const mjCPlugin& other) { |
| | if (this != &other) { |
| | this->spec = other.spec; |
| | *static_cast<mjCPlugin_*>(this) = static_cast<const mjCPlugin_&>(other); |
| | parent = this; |
| | plugin_slot = other.plugin_slot; |
| | } |
| | PointToLocal(); |
| | return *this; |
| | } |
| |
|
| |
|
| |
|
| | void mjCPlugin::PointToLocal() { |
| | spec.element = static_cast<mjsElement*>(this); |
| | spec.name = &name; |
| | spec.info = &info; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjCPlugin::Compile(void) { |
| | mjCPlugin* plugin_instance = this; |
| | model->ResolvePlugin(this, plugin_name, name, &plugin_instance); |
| | const mjpPlugin* plugin = mjp_getPluginAtSlot(plugin_slot); |
| |
|
| | |
| | flattened_attributes.clear(); |
| | std::map<std::string, std::string, std::less<> > config_attribs_copy = config_attribs; |
| |
|
| | |
| | |
| | |
| | for (int i = 0; i < plugin->nattribute; ++i) { |
| | std::string_view attr(plugin->attributes[i]); |
| | auto it = config_attribs_copy.find(attr); |
| | if (it == config_attribs_copy.end()) { |
| | flattened_attributes.push_back('\0'); |
| | } else { |
| | auto original_size = flattened_attributes.size(); |
| | flattened_attributes.resize(original_size + it->second.size() + 1); |
| | std::memcpy(&flattened_attributes[original_size], it->second.c_str(), |
| | it->second.size() + 1); |
| | config_attribs_copy.erase(it); |
| | } |
| | } |
| |
|
| | |
| | if (plugin->nattribute == 0) { |
| | flattened_attributes.push_back('\0'); |
| | } |
| |
|
| | |
| | if (!config_attribs_copy.empty()) { |
| | std::string error = |
| | "unrecognized attribute 'plugin:" + config_attribs_copy.begin()->first + |
| | "' for plugin " + std::string(plugin->name) + "'"; |
| | throw mjCError(parent, "%s", error.c_str()); |
| | } |
| | } |
| |
|