Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
8 changes: 7 additions & 1 deletion docs/source/unitree_interfaces.md
Original file line number Diff line number Diff line change
Expand Up @@ -97,4 +97,10 @@ Note that to avoid conflicts between `button` indices and `axis` indices (and is
2. Turn the robot on.
3. Once robot signifies ready state (zero torque mode on G1 humanoid, standing up on Go2 quadruped), run fsm.
4. Start with INIT -> DAMPING, and follow up with DAMPING -> USER_POSE (for the G1), or proceed directly with INIT -> USER_POSE (for the Go2).
5. Proceed with USER_POSE -> USER_CTRL for user defined controllers.
5. Proceed with USER_POSE -> USER_CTRL for user defined controllers.

## Debugging
You can also check what the default button mappings are by running:
```
obk-launch config=unitree_fsm_debug.yaml device=onboard
```
10 changes: 5 additions & 5 deletions obelisk/cpp/hardware/include/unitree_joystick.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ namespace obelisk {
Y1 = static_cast<int>(Y) + LAYER_OFFSET,
A1 = static_cast<int>(A) + LAYER_OFFSET,
B1 = static_cast<int>(B) + LAYER_OFFSET,
DR1 = static_cast<int>(DL) + LAYER_OFFSET,
DL1 = static_cast<int>(DR) + LAYER_OFFSET,
DR1 = static_cast<int>(DR) + LAYER_OFFSET,
DL1 = static_cast<int>(DL) + LAYER_OFFSET,
DU1 = static_cast<int>(DU) + LAYER_OFFSET,
DD1 = static_cast<int>(DD) + LAYER_OFFSET,
};
Expand Down Expand Up @@ -325,9 +325,9 @@ namespace obelisk {
// DPAD lives in axes; positive/negative handled via sign in detection
int ax = code - AXIS_OFFSET;
// For negative variants (Left/Down), normalize like getButton() does
if (code == static_cast<int>(ButtonMap::DL) ||
if (code == static_cast<int>(ButtonMap::DR) ||
code == static_cast<int>(ButtonMap::DD) ||
code == static_cast<int>(ButtonMap::DL1) ||
code == static_cast<int>(ButtonMap::DR1) ||
code == static_cast<int>(ButtonMap::DD1)) {
ax -= NEG_OFFSET; // mirror your detection
}
Expand Down Expand Up @@ -391,7 +391,7 @@ namespace obelisk {
}
if (on_dpad) {
int sgn = 1;
if (btn == static_cast<int>(ButtonMap::DL) || btn == static_cast<int>(ButtonMap::DD) || btn == static_cast<int>(ButtonMap::DL1) || btn == static_cast<int>(ButtonMap::DD1)) {
if (btn == static_cast<int>(ButtonMap::DR) || btn == static_cast<int>(ButtonMap::DD)) {
btn -= NEG_OFFSET;
sgn = -1;
}
Expand Down
2 changes: 1 addition & 1 deletion obelisk/cpp/hardware/robots/unitree/unitree_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ namespace obelisk {
RCLCPP_INFO_STREAM(this->get_logger(), "EXECUTION FSM STATE TRANSITIONED TO " << TRANSITION_STRINGS.at(exec_fsm_state_));
} else {
if (exec_fsm_state_ == cmd_exec_fsm_state) {
RCLCPP_INFO_STREAM(this->get_logger(), "EXECUTION FSM AREADY IN COMMANDED STATE " << TRANSITION_STRINGS.at(exec_fsm_state_));
RCLCPP_INFO_STREAM(this->get_logger(), "EXECUTION FSM ALREADY IN COMMANDED STATE " << TRANSITION_STRINGS.at(exec_fsm_state_));
} else {
RCLCPP_ERROR_STREAM(this->get_logger(), "EXECUTION FSM COMMAND INVALID: " << TRANSITION_STRINGS.at(exec_fsm_state_) << " -> " << TRANSITION_STRINGS.at(cmd_exec_fsm_state));
}
Expand Down