Skip to content

Commit ec268e7

Browse files
dbellicoso-bdaiexploy-bot
authored andcommitted
Extend support for body input components
### What change is being made Add support for body twist matchers and fix support for deployment of policies exported with mjlab. This PR adds missing deployment matchers and addresses existing ones for body components: - Add matchers for body twists - Body matchers were previously only supporting "obj.BODY_CONFIG_NAME.bodies.BODY_LINK_NAME.suffix". This PR changes matchers to support body inputs which drop the "bodies" string in their name. ### Why this change is being made Support deployment of policies that require body twist inputs. ### Tested Tests cover new matchers. Deployed in sim and on hardware. GitOrigin-RevId: 54379a8fe98d40f30b9ff4b4f186f4134b978296
1 parent 1224daa commit ec268e7

18 files changed

Lines changed: 1732 additions & 1148 deletions

File tree

.github/workflows/docs.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ jobs:
3939
- name: Setup pixi
4040
uses: prefix-dev/setup-pixi@v0.9.5
4141
with:
42-
pixi-version: latest
42+
pixi-version: v0.67.2
4343
frozen: true
4444
cache: true
4545
environments: docs

.github/workflows/test.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ jobs:
3232
- name: Setup pixi
3333
uses: prefix-dev/setup-pixi@v0.9.5
3434
with:
35-
pixi-version: latest
35+
pixi-version: v0.67.2
3636
frozen: true
3737
cache: false
3838

@@ -50,7 +50,7 @@ jobs:
5050
- name: Setup pixi
5151
uses: prefix-dev/setup-pixi@v0.9.5
5252
with:
53-
pixi-version: latest
53+
pixi-version: v0.67.2
5454
frozen: true
5555
cache: false
5656

@@ -71,7 +71,7 @@ jobs:
7171
- name: Setup pixi
7272
uses: prefix-dev/setup-pixi@v0.9.5
7373
with:
74-
pixi-version: latest
74+
pixi-version: v0.67.2
7575
frozen: true
7676
cache: false
7777

control/include/exploy/components.hpp

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ namespace exploy::control {
1717
* input tensors. Subclasses implement specific data sources (joints, IMU, cameras, etc.).
1818
*/
1919
struct Input {
20+
explicit Input(const std::string& name) : name_(name) {}
2021
virtual ~Input() = default;
2122

2223
/**
@@ -42,6 +43,15 @@ struct Input {
4243
*/
4344
virtual bool read(OnnxRuntime& runtime, RobotStateInterface& state,
4445
CommandInterface& command) = 0;
46+
47+
/**
48+
* @brief Get the name of this component.
49+
* @return Name of this component.
50+
*/
51+
virtual const std::string& getName() const { return name_; }
52+
53+
private:
54+
std::string name_; ///< Name of this component.
4555
};
4656

4757
/**
@@ -52,6 +62,7 @@ struct Input {
5262
* velocity commands, memory buffers, etc.).
5363
*/
5464
struct Output {
65+
explicit Output(const std::string& name) : name_(name) {}
5566
virtual ~Output() = default;
5667

5768
/**
@@ -77,6 +88,15 @@ struct Output {
7788
*/
7889
virtual bool write(OnnxRuntime& runtime, RobotStateInterface& state,
7990
CommandInterface& command) = 0;
91+
92+
/**
93+
* @brief Get the name of this component.
94+
* @return Name of this component.
95+
*/
96+
virtual const std::string& getName() const { return name_; }
97+
98+
private:
99+
std::string name_; ///< Name of this component.
80100
};
81101

82102
/**
@@ -432,6 +452,54 @@ class BodyPositionInput : public Input {
432452
std::string body_name_; ///< Rigid body name.
433453
};
434454

455+
/**
456+
* @brief Input component that reads linear velocity of a specific rigid body.
457+
*
458+
* Reads the linear velocity of a named rigid body as a 3D vector (vx, vy, vz)
459+
* and copies it to the ONNX input buffer.
460+
*/
461+
class BodyLinearVelocityInput : public Input {
462+
public:
463+
/**
464+
* @brief Construct a body linear velocity input component.
465+
*
466+
* @param key ONNX input tensor name (e.g., "obj.object.box.lin_vel_b_rt_w_in_b").
467+
* @param body_name Name of the rigid body to read linear velocity from.
468+
*/
469+
BodyLinearVelocityInput(const std::string& key, const std::string& body_name);
470+
471+
bool init(RobotStateInterface& state, CommandInterface& command) override;
472+
bool read(OnnxRuntime& runtime, RobotStateInterface& state, CommandInterface& command) override;
473+
474+
private:
475+
std::string key_; ///< ONNX input tensor name.
476+
std::string body_name_; ///< Rigid body name.
477+
};
478+
479+
/**
480+
* @brief Input component that reads angular velocity of a specific rigid body.
481+
*
482+
* Reads the angular velocity of a named rigid body as a 3D vector (wx, wy, wz)
483+
* and copies it to the ONNX input buffer.
484+
*/
485+
class BodyAngularVelocityInput : public Input {
486+
public:
487+
/**
488+
* @brief Construct a body angular velocity input component.
489+
*
490+
* @param key ONNX input tensor name (e.g., "obj.object.box.ang_vel_b_rt_w_in_b").
491+
* @param body_name Name of the rigid body to read angular velocity from.
492+
*/
493+
BodyAngularVelocityInput(const std::string& key, const std::string& body_name);
494+
495+
bool init(RobotStateInterface& state, CommandInterface& command) override;
496+
bool read(OnnxRuntime& runtime, RobotStateInterface& state, CommandInterface& command) override;
497+
498+
private:
499+
std::string key_; ///< ONNX input tensor name.
500+
std::string body_name_; ///< Rigid body name.
501+
};
502+
435503
/**
436504
* @brief Input component that reads commanded SE(3) pose.
437505
*

control/include/exploy/controller.hpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,18 @@ class OnnxRLController {
3737
* This function only parses the configuration needed to interface with the ONNX model. Call
3838
* init() to fully initialize the controller.
3939
*
40+
* If called more than once (e.g. to reload a model), default matchers are registered only on
41+
* the first call where register_default_matchers is true; custom matchers added via context()
42+
* are preserved across calls.
43+
*
4044
* @param onnx_model_path Path to the ONNX model file.
45+
* @param register_default_matchers If true (default), all built-in matchers (including
46+
* StepCountMatcher) are registered the first time create() is called with this parameter set to
47+
* true. Passing false disables all built-in matchers for that call; only matchers added via
48+
* context() will be used, and a later call with true can still register the built-in matchers.
4149
* @return True if parsing succeeds, false otherwise.
4250
*/
43-
bool create(const std::string& onnx_model_path);
51+
bool create(const std::string& onnx_model_path, bool register_default_matchers = true);
4452
/**
4553
* @brief Initialize the controller.
4654
*
@@ -72,6 +80,8 @@ class OnnxRLController {
7280
RobotStateInterface& state_;
7381
CommandInterface& command_;
7482

83+
bool default_matchers_registered_{false};
84+
7585
// Data collection.
7686
DataCollectionInterface& data_collection_;
7787
double inference_duration_s_{};

0 commit comments

Comments
 (0)