Skip to content

Commit ef6c32e

Browse files
committed
yay
1 parent b1d4f1c commit ef6c32e

File tree

6 files changed

+115
-35
lines changed

6 files changed

+115
-35
lines changed

docker-compose.yml

Lines changed: 1 addition & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -115,24 +115,4 @@ services:
115115
capabilities: [gpu]
116116
tty: true
117117
stdin_open: true
118-
network_mode: host
119-
rover_x11: # Do not use if you don't have a nvidia GPU with supported cuda cores
120-
build:
121-
context: .
122-
dockerfile: Dockerfile
123-
image: roverflake2:dev
124-
container_name: rover_dev
125-
working_dir: /RoverFlake2
126-
tty: true
127-
stdin_open: true
128-
volumes: # Purpose: docker env watches for changes in repo and updates
129-
# preferred method is to specify a directory
130-
# e.g. '- ./node_practice:/RoverFlake2/node_practice'
131-
# Bind-mount the whole repo into the container
132-
- ./:/RoverFlake2
133-
- /tmp/.X11-unix:/tmp/.X11-unix # GUI compatibility
134-
environment:
135-
- DISPLAY=${DISPLAY}
136-
- ROVERFLAKE_ROOT=/RoverFlake2
137-
- MUJOCO_GL=glfw # or egl (headless GUI)
138-
network_mode: host
118+
network_mode: host

src/arm_control/include/controller_config.h

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -268,8 +268,4 @@ namespace ArmControllerConfig { // Can make into a class later?
268268
// return true;
269269
// }
270270
// }
271-
}
272-
273-
#else
274-
#pragma warning "Warning: No valid ACTIVE_CONTROLLER defined in controller_config.h"
275-
#endif
271+
}

src/arm_control/src/joy_arm_control.cpp

Lines changed: 24 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,30 @@
11
#include "joy_arm_control.h"
22
#include <cmath>
33

4+
// Cartesian / IK-mode constants (used by MoveIt Servo twist path)
5+
namespace ControllerConfig {
6+
constexpr const char* CART_FRAME_ID = "base_link";
7+
constexpr double CART_BUTTON_SPEED = 0.5;
8+
constexpr double ROT_STICK_SPEED = 1.0;
9+
constexpr double AXIS_DEADZONE = 0.1;
10+
11+
constexpr int BTN_CART_POS_X = switch_index::buttons::DPAD_UP;
12+
constexpr int BTN_CART_NEG_X = switch_index::buttons::DPAD_DOWN;
13+
constexpr int BTN_CART_POS_Y = switch_index::buttons::DPAD_RIGHT;
14+
constexpr int BTN_CART_NEG_Y = switch_index::buttons::DPAD_LEFT;
15+
constexpr int BTN_CART_POS_Z = switch_index::buttons::Y;
16+
constexpr int BTN_CART_NEG_Z = switch_index::buttons::A;
17+
18+
constexpr int AXIS_ROLL = switch_index::axes::RIGHT_JOYSTICK_X;
19+
constexpr bool INVERT_ROLL = false;
20+
constexpr int AXIS_PITCH = switch_index::axes::RIGHT_JOYSTICK_Y;
21+
constexpr bool INVERT_PITCH = false;
22+
constexpr int AXIS_YAW = switch_index::axes::LEFT_JOYSTICK_X;
23+
constexpr bool INVERT_YAW = false;
24+
25+
constexpr int BTN_GRIPPER_TOGGLE = switch_index::buttons::R1;
26+
}
27+
428
// Constructor
529
ArmJoy::ArmJoy() :
630
Node("arm_joy_control")
@@ -37,13 +61,6 @@ Node("arm_joy_control")
3761
};
3862

3963
RCLCPP_INFO(this->get_logger(), "=== ArmJoy started ===");
40-
#if ACTIVE_CONTROLLER == CONTROLLER_PRO_CONTROLLER
41-
RCLCPP_INFO(this->get_logger(), "Active controller: Nintendo Switch Pro Controller");
42-
#elif ACTIVE_CONTROLLER == CONTROLLER_CYBORG_STICK
43-
RCLCPP_INFO(this->get_logger(), "Active controller: Saitek Cyborg USB Stick");
44-
#else
45-
RCLCPP_INFO(this->get_logger(), "Active controller: Unknown");
46-
#endif
4764
RCLCPP_INFO(this->get_logger(), "Cartesian frame: %s | Button speed: %.2f",
4865
ControllerConfig::CART_FRAME_ID, ControllerConfig::CART_BUTTON_SPEED);
4966
}

src/arm_hardware_interface/CMakeLists.txt

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,18 @@ add_executable(
3333
src/moteus_CAN_interface/MoteusInterface.cpp
3434
src/moteus_CAN_interface/MoteusIO.cpp)
3535

36+
add_executable(moteus_poll src/poll.cpp)
37+
3638
target_compile_definitions(moteus_arm_driver PRIVATE BUILDING_NEW_DRIVER=1) #??
3739

3840
target_link_libraries(moteus_arm_driver moteus::cpp)
41+
target_link_libraries(moteus_poll moteus::cpp)
3942
ament_target_dependencies(serial_arm_driver rclcpp sensor_msgs serial
4043
rover_msgs arm_control)
4144
ament_target_dependencies(moteus_arm_driver rclcpp sensor_msgs serial
42-
rover_msgs arm_control std_msgs)
45+
rover_msgs arm_control std_msgs)
46+
47+
ament_target_dependencies(moteus_poll rclcpp)
4348

4449
if(BUILD_TESTING)
4550
find_package(ament_lint_auto REQUIRED)
@@ -58,7 +63,7 @@ install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/launch)
5863
install(DIRECTORY include/ DESTINATION include/)
5964

6065
install(
61-
TARGETS serial_arm_driver moteus_arm_driver ${PROJECT_NAME}
66+
TARGETS serial_arm_driver moteus_arm_driver moteus_poll ${PROJECT_NAME}
6267
DESTINATION lib/${PROJECT_NAME}
6368
ARCHIVE DESTINATION lib
6469
LIBRARY DESTINATION lib)
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
#pragma once
2+
3+
#include <chrono>
4+
#include <memory>
5+
#include <vector>
6+
#include "rclcpp/rclcpp.hpp"
7+
8+
#include "moteus.h"
9+
10+
namespace moteus = mjbots::moteus;
11+
12+
#define NUM_JOINTS 6
13+
14+
class MoteusPoll : public rclcpp::Node {
15+
public:
16+
MoteusPoll();
17+
18+
private:
19+
void poll();
20+
21+
std::vector<std::shared_ptr<moteus::Controller>> controllers_;
22+
std::shared_ptr<moteus::Transport> transport_;
23+
rclcpp::TimerBase::SharedPtr timer_;
24+
};
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
#include "moteus_poll.h"
2+
3+
MoteusPoll::MoteusPoll() : Node("moteus_poll") {
4+
transport_ = moteus::Controller::MakeSingletonTransport({});
5+
6+
for (int id = 1; id <= NUM_JOINTS; id++) {
7+
moteus::Controller::Options opts;
8+
opts.id = id;
9+
auto controller = std::make_shared<moteus::Controller>(opts);
10+
controllers_.push_back(controller);
11+
}
12+
13+
timer_ = this->create_wall_timer(
14+
std::chrono::milliseconds(100),
15+
std::bind(&MoteusPoll::poll, this)
16+
);
17+
18+
RCLCPP_INFO(this->get_logger(), "Polling %d motors at 10 Hz", NUM_JOINTS);
19+
}
20+
21+
void MoteusPoll::poll() {
22+
std::vector<moteus::CanFdFrame> command_frames;
23+
24+
for (auto& controller : controllers_) {
25+
command_frames.push_back(controller->MakeQuery());
26+
}
27+
28+
std::vector<moteus::CanFdFrame> replies;
29+
transport_->BlockingCycle(command_frames.data(), command_frames.size(), &replies);
30+
31+
for (const auto& frame : replies) {
32+
int motor_id = frame.source;
33+
auto result = moteus::Query::Parse(frame.data, frame.size);
34+
35+
RCLCPP_INFO(this->get_logger(),
36+
"ID: %d | Mode: %2d | Fault: %2d | "
37+
"Pos: %.3f rev | Vel: %.3f rev/s | Torque: %.3f Nm | "
38+
"Voltage: %.1f V | Temp: %.1f C",
39+
motor_id,
40+
static_cast<int>(result.mode),
41+
static_cast<int>(result.fault),
42+
result.position,
43+
result.velocity,
44+
result.torque,
45+
result.voltage,
46+
result.temperature
47+
);
48+
}
49+
50+
RCLCPP_INFO(this->get_logger(), "---");
51+
}
52+
53+
int main(int argc, char* argv[]) {
54+
rclcpp::init(argc, argv);
55+
rclcpp::spin(std::make_shared<MoteusPoll>());
56+
rclcpp::shutdown();
57+
return 0;
58+
}

0 commit comments

Comments
 (0)