Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions src/viam/sdk/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ target_sources(viamsdk
module/service.cpp
module/private/data_consumer_query.cpp
referenceframe/frame.cpp
referenceframe/kinematics_model_table.cpp
registry/registry.cpp
resource/resource.cpp
resource/resource_api.cpp
Expand Down Expand Up @@ -219,6 +220,7 @@ target_sources(viamsdk
../../viam/sdk/module/service.hpp
../../viam/sdk/module/signal_manager.hpp
../../viam/sdk/referenceframe/frame.hpp
../../viam/sdk/referenceframe/kinematics_model_table.hpp
../../viam/sdk/registry/registry.hpp
../../viam/sdk/resource/resource.hpp
../../viam/sdk/resource/resource_api.hpp
Expand Down
8 changes: 8 additions & 0 deletions src/viam/sdk/common/linear_algebra.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,14 @@ struct Vector3 {
std::array<scalar_type, 3> data;
};

inline bool operator==(const Vector3& a, const Vector3& b) {
return a.data == b.data;
}

inline bool operator!=(const Vector3& a, const Vector3& b) {
Comment thread
acmorrow marked this conversation as resolved.
return !(a == b);
}

namespace proto_convert_details {

template <>
Expand Down
287 changes: 287 additions & 0 deletions src/viam/sdk/referenceframe/kinematics_model_table.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,287 @@
#include <viam/sdk/referenceframe/kinematics_model_table.hpp>

#include <set>
#include <sstream>
#include <unordered_map>
#include <unordered_set>

#include <boost/property_tree/ptree.hpp>
#include <boost/property_tree/xml_parser.hpp>

#if defined(__has_include) && (__has_include(<xtensor/generators/xbuilder.hpp>))
#include <xtensor/generators/xbuilder.hpp>
#else
#include <xtensor/xbuilder.hpp>
#endif
#if defined(__has_include) && (__has_include(<xtensor/containers/xarray.hpp>))
#include <xtensor/containers/xarray.hpp>
#else
#include <xtensor/xarray.hpp>
#endif

#include <viam/sdk/common/exception.hpp>
#include <viam/sdk/common/utils.hpp>
#include <viam/sdk/referenceframe/private/kinematics_model_table_internals.hpp>

namespace viam {
namespace sdk {
namespace impl {

namespace {

Vector3 parse_triple(const std::string& s) {
std::istringstream iss(s);
double x = 0;
double y = 0;
double z = 0;
if (!(iss >> x >> y >> z)) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: failed to parse space-delimited triple: '" + s + "'");
}
return Vector3{x, y, z};
}

} // namespace

// The row/type are nested in ModelTable; alias them for brevity in the
// URDF-pipeline helpers below.
using JointRow = ModelTable::JointRow;
using JointType = ModelTable::JointType;

std::vector<ParsedJoint> parse_urdf(const KinematicsDataURDF& urdf) {
namespace pt = boost::property_tree;
pt::ptree tree;
const std::string text = bytes_to_string(urdf.bytes);
std::istringstream iss(text);
try {
pt::read_xml(iss, tree);
} catch (const pt::xml_parser_error& e) {
throw Exception(ErrorCondition::k_general,
std::string("URDFToModelTable: failed to parse URDF XML: ") + e.what());
}

const auto robot_it = tree.find("robot");
if (robot_it == tree.not_found()) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: no <robot> root element in URDF");
}
const pt::ptree& robot = robot_it->second;

std::vector<ParsedJoint> joints;
for (const auto& child : robot) {
if (child.first != "joint") {
continue;
}
const pt::ptree& jnode = child.second;

ParsedJoint j;
j.name = jnode.get<std::string>("<xmlattr>.name", "");
j.type_str = jnode.get<std::string>("<xmlattr>.type", "");
j.parent_link = jnode.get<std::string>("parent.<xmlattr>.link", "");
j.child_link = jnode.get<std::string>("child.<xmlattr>.link", "");

if (j.type_str.empty() || j.parent_link.empty() || j.child_link.empty()) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: joint '" + j.name +
"' missing required attribute (type/parent/child)");
}

const auto origin_opt = jnode.get_child_optional("origin");
if (origin_opt) {
j.xyz = parse_triple(origin_opt->get<std::string>("<xmlattr>.xyz", "0 0 0"));
j.rpy = parse_triple(origin_opt->get<std::string>("<xmlattr>.rpy", "0 0 0"));
}
const auto axis_opt_node = jnode.get_child_optional("axis");
if (axis_opt_node) {
j.axis_opt = parse_triple(axis_opt_node->get<std::string>("<xmlattr>.xyz", "1 0 0"));
}
joints.push_back(std::move(j));
}
return joints;
}

std::vector<ParsedJoint> walk_urdf_chain(const std::vector<ParsedJoint>& joints) {
std::unordered_map<std::string, std::vector<const ParsedJoint*>> by_parent;
std::set<std::string> all_parents;
std::unordered_set<std::string> all_children;
for (const auto& j : joints) {
by_parent[j.parent_link].push_back(&j);
all_parents.insert(j.parent_link);
all_children.insert(j.child_link);
}

std::vector<std::string> roots;
for (const auto& p : all_parents) {
if (all_children.find(p) == all_children.end()) {
roots.push_back(p);
}
}
if (roots.size() != 1) {
std::string list;
for (const auto& r : roots) {
list += "'" + r + "' ";
}
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: expected exactly one root link, found " +
std::to_string(roots.size()) + ": " + list);
}

std::vector<ParsedJoint> ordered;
ordered.reserve(joints.size());
std::unordered_set<std::string> visited;
std::string current = roots[0];
while (true) {
if (!visited.insert(current).second) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: cycle in URDF chain at link '" + current + "'");
}
auto it = by_parent.find(current);
if (it == by_parent.end() || it->second.empty()) {
break;
}
if (it->second.size() > 1) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: branching topology at link '" + current + "' (" +
std::to_string(it->second.size()) + " outgoing joints)");
}
const ParsedJoint* j = it->second.front();
ordered.push_back(*j);
current = j->child_link;
}
if (ordered.size() != joints.size()) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: chain walk visited " + std::to_string(ordered.size()) +
" of " + std::to_string(joints.size()) + " joints");
}
return ordered;
}

JointRow to_row(const ParsedJoint& parsed) {
JointRow row;
row.name = parsed.name;
row.xyz = parsed.xyz;
row.rpy = parsed.rpy;

if (parsed.type_str == "revolute") {

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wonder if we want a public to_string or joint_type_from_string ?

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am not convinced that we need a public to_string or joint_type_from_string.
My reasoning is that users always get a parsed JointType values values via from(urdf) / from(tensor) and never see the strings.
The to_string has no user anywhere in this flow.

row.type = JointType::k_revolute;
} else if (parsed.type_str == "continuous") {
row.type = JointType::k_continuous;
} else if (parsed.type_str == "prismatic") {
row.type = JointType::k_prismatic;
} else if (parsed.type_str == "fixed") {
row.type = JointType::k_fixed;
} else {
throw Exception(ErrorCondition::k_not_supported,
"URDFToModelTable: joint '" + parsed.name + "' has unsupported type '" +
parsed.type_str +
"' (supported: revolute, continuous, prismatic, fixed)");
}

if (row.type == JointType::k_fixed) {
row.axis = Vector3{0, 0, 0};
} else if (parsed.axis_opt) {
if (*parsed.axis_opt == Vector3{}) {
throw Exception(ErrorCondition::k_general,
"URDFToModelTable: joint '" + parsed.name + "' has zero axis");
}
row.axis = *parsed.axis_opt;
} else {
row.axis = Vector3{1, 0, 0}; // URDF default
}
return row;
}

} // namespace impl

ModelTable::ModelTable(std::vector<ModelTable::JointRow> rows) : rows_(std::move(rows)) {}

ModelTable ModelTable::from(const KinematicsDataURDF& urdf) {
using namespace impl;
auto chain = walk_urdf_chain(parse_urdf(urdf));
std::vector<JointRow> rows;
rows.reserve(chain.size());
for (const auto& j : chain) {
rows.push_back(to_row(j));
}
return ModelTable(std::move(rows));
}

xt::xarray<double> ModelTable::to_tensor() const {
if (rows_.empty()) {
throw Exception(ErrorCondition::k_general, "ModelTable::to_tensor: empty model table");
}
xt::xarray<double> out = xt::zeros<double>({rows_.size(), std::size_t{10}});
for (std::size_t i = 0; i < rows_.size(); ++i) {
const auto& r = rows_[i];
out(i, 0) = r.xyz.x();

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't love this but struggling to come up with an alternative

    int idx = 0;
    for (const auto& vec3 : {std::cref(r.xyz), std::cref(r.rpy), std::cref(r.axis)}) {
        for (const auto& val : arr.data) {
            out(i, idx++) = val;
        }
    }

honestly not sure if this is preferable, your call

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

while more compact/abstract, I think that what we have now is slightly clearer to read.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in that case maybe just a line break between the blocks where you're operating on the different vec3's

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done!

out(i, 1) = r.xyz.y();
out(i, 2) = r.xyz.z();

out(i, 3) = r.rpy.x();
out(i, 4) = r.rpy.y();
out(i, 5) = r.rpy.z();

out(i, 6) = r.axis.x();
out(i, 7) = r.axis.y();
out(i, 8) = r.axis.z();

out(i, 9) = static_cast<double>(static_cast<int>(r.type));
}
return out;
}

ModelTable ModelTable::from(const xt::xarray<double>& tensor) {
if (tensor.dimension() != 2) {
throw Exception(ErrorCondition::k_general,
"ModelTable::from(tensor): expected 2D tensor, got " +
std::to_string(tensor.dimension()) + "D");
}
if (tensor.shape()[1] != 10) {
throw Exception(ErrorCondition::k_general,
"ModelTable::from(tensor): expected shape (n, 10), got (n, " +
std::to_string(tensor.shape()[1]) + ")");
}
if (tensor.shape()[0] == 0) {
throw Exception(ErrorCondition::k_general, "ModelTable::from(tensor): empty tensor");
}
std::vector<JointRow> rows;
rows.reserve(tensor.shape()[0]);
for (std::size_t i = 0; i < tensor.shape()[0]; ++i) {
const double type_v = tensor(i, 9);
const int type_i = static_cast<int>(type_v);
if (static_cast<double>(type_i) != type_v) {
throw Exception(ErrorCondition::k_general,
"ModelTable::from(tensor): row " + std::to_string(i) +
" joint type value " + std::to_string(type_v) +
" is not an integer");
}
JointType joint_type;
switch (static_cast<JointType>(type_i)) {
case JointType::k_revolute:
case JointType::k_continuous:
case JointType::k_prismatic:
case JointType::k_fixed:
joint_type = static_cast<JointType>(type_i);
break;
default:
throw Exception(ErrorCondition::k_general,
"ModelTable::from(tensor): row " + std::to_string(i) +
" joint type value " + std::to_string(type_i) +
" does not match any JointType");
}
JointRow row;
row.xyz = Vector3{tensor(i, 0), tensor(i, 1), tensor(i, 2)};
row.rpy = Vector3{tensor(i, 3), tensor(i, 4), tensor(i, 5)};
row.axis = Vector3{tensor(i, 6), tensor(i, 7), tensor(i, 8)};
row.type = joint_type;
rows.push_back(std::move(row));
}
return ModelTable(std::move(rows));
}

const std::vector<ModelTable::JointRow>& ModelTable::rows() const {
return rows_;
}

} // namespace sdk
} // namespace viam
76 changes: 76 additions & 0 deletions src/viam/sdk/referenceframe/kinematics_model_table.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/// @file referenceframe/kinematics_model_table.hpp
/// @brief A per-joint model table for a serial kinematic chain, with
/// conversions to/from URDF and a double (n, 10) tensor.
#pragma once

#include <string>
#include <vector>

#if defined(__has_include) && (__has_include(<xtensor/containers/xarray.hpp>))
#include <xtensor/containers/xarray.hpp>
#else
#include <xtensor/xarray.hpp>
#endif

#include <viam/sdk/common/kinematics.hpp>
#include <viam/sdk/common/linear_algebra.hpp>

namespace viam {
namespace sdk {

/// @brief A per-joint model table for a serial kinematic chain, held in chain
/// order. Build one with the `from` factories and read it back via `rows()` or
/// `to_tensor()`.
class ModelTable {
public:
/// @brief URDF joint type, restricted to arm-relevant joints.
/// @note Underlying values are stable and form the wire encoding for
/// column 9 of the tensor produced by `to_tensor()`.
enum class JointType {

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I suspect the linter is going to want you to give this a smaller integral type.

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A bit confused by this, the linter did not complain.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, maybe we don't do that anymore.

k_revolute = 0,
k_continuous = 1,
k_prismatic = 2,
k_fixed = 3,
};

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are there any connections between the set of possible values of these vectors, and the types of joints?

You could consider adding static factory methods on JointRow, like JointRow::fixed(std::string name, ...).

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

xyz and rpy just tell us the position and orientation of "things", eg. links.
axis is our biggest hint here.
If it's (0, 0, 0) then we can deduce that it's a fixed joint with certainty.
But on the other hand if it's a non-zero unit vector we do not have a way of knowing if the joint type is revolute, continuous or prismatic.

/// @brief One row of the model table: the per-joint URDF fields.
/// @note `xyz`/`rpy`/`axis` are taken directly from the URDF.
struct JointRow {
std::string name;
Vector3 xyz{};
Vector3 rpy{};
Vector3 axis{};
JointType type = JointType::k_fixed;
};

/// @brief Construct directly from rows already in chain order.
explicit ModelTable(std::vector<JointRow> rows);

/// @brief Parse a kinematics description into a model table in chain order.
/// @throws viam::sdk::Exception on parse error, branching / multi-root /
/// disconnected topology, unsupported joint types, or zero axis.
static ModelTable from(const KinematicsDataURDF& urdf);

/// @brief Inverse of `to_tensor`: rehydrate an (n, 10) double tensor into a
/// model table. Reconstructed rows have empty `name` (names are not carried
/// in the tensor).
/// @throws viam::sdk::Exception on non-2D input, wrong column count, empty
/// input, or invalid joint-type encoding (col 9 must be an integer matching
/// one of the `JointType` values).
static ModelTable from(const xt::xarray<double>& tensor);

/// @brief Convert to a double tensor of shape (n, 10).
/// Columns: 0..2 xyz, 3..5 rpy, 6..8 axis, 9 joint type as the underlying
/// value of `JointType` (see enum declaration for the encoding).
/// @throws viam::sdk::Exception on empty table.
xt::xarray<double> to_tensor() const;

/// @brief The rows of the table, in chain order.
const std::vector<JointRow>& rows() const;

private:
std::vector<JointRow> rows_;
};

} // namespace sdk
} // namespace viam
Loading
Loading