Skip to content

Commit

Permalink
tweaks
Browse files Browse the repository at this point in the history
  • Loading branch information
manglemix committed May 4, 2024
1 parent 757acda commit 21f7361
Show file tree
Hide file tree
Showing 8 changed files with 87 additions and 63 deletions.
1 change: 0 additions & 1 deletion Cargo.lock

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

4 changes: 2 additions & 2 deletions lunabotics/lunabase-lib/src/telemetry.rs
Original file line number Diff line number Diff line change
Expand Up @@ -484,7 +484,7 @@ impl LunabotConn {
fn tilt_bucket_up(&self) {
let shared = self.shared.as_ref().unwrap();
let mut controls_packet = shared.controls_data.load();
controls_packet.arm_params.tilt = ArmAction::Extend;
controls_packet.arm_params.tilt = ArmAction::Retract;
shared.controls_data.store(controls_packet);
shared.echo_controls.store(true, Ordering::Relaxed);
}
Expand All @@ -493,7 +493,7 @@ impl LunabotConn {
fn tilt_bucket_down(&self) {
let shared = self.shared.as_ref().unwrap();
let mut controls_packet = shared.controls_data.load();
controls_packet.arm_params.tilt = ArmAction::Retract;
controls_packet.arm_params.tilt = ArmAction::Extend;
shared.controls_data.store(controls_packet);
shared.echo_controls.store(true, Ordering::Relaxed);
}
Expand Down
16 changes: 8 additions & 8 deletions lunabotics/lunabase/lunabase.gdextension
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@ compatibility_minimum = 4.1
reloadable = true

[libraries]
linux.debug.x86_64 = "res://../target/debug/liblunabase_lib.so"
linux.release.x86_64 = "res://../target/release/liblunabase_lib.so"
windows.debug.x86_64 = "res://../target/release/lunabase_lib.dll"
windows.release.x86_64 = "res://../target/release/lunabase_lib.dll"
macos.debug = "res://../target/debug/liblunabase_lib.dylib"
macos.release = "res://../target/release/liblunabase_lib.dylib"
macos.debug.arm64 = "res://../target/debug/liblunabase_lib.dylib"
macos.release.arm64 = "res://../target/release/liblunabase_lib.dylib"
linux.debug.x86_64 = "res://../../target/debug/liblunabase_lib.so"
linux.release.x86_64 = "res://../../target/release/liblunabase_lib.so"
windows.debug.x86_64 = "res://../../target/release/lunabase_lib.dll"
windows.release.x86_64 = "res://../../target/release/lunabase_lib.dll"
macos.debug = "res://../../target/debug/liblunabase_lib.dylib"
macos.release = "res://../../target/release/liblunabase_lib.dylib"
macos.debug.arm64 = "res://../../target/debug/liblunabase_lib.dylib"
macos.release.arm64 = "res://../../target/release/liblunabase_lib.dylib"
22 changes: 14 additions & 8 deletions lunabotics/lunabase/lunabase.tscn
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ func _input(event: InputEvent) -> void:

elif event.is_action_pressed(\"Restart\"):
get_tree().change_scene_to_file(scene_file_path)

elif event.is_action_pressed(\"NextCamera\"):
Lunabot.next_camera()

elif event.is_action_pressed(\"PreviousCamera\"):
Lunabot.previous_camera()
"
[sub_resource type="GDScript" id="GDScript_wemvy"]
Expand Down Expand Up @@ -96,14 +102,14 @@ func _on_pressed() -> void:


func _on_button_up() -> void:
Lunabot.stop_arm()
Lunabot.stop_tilt_bucket()


func _input(event: InputEvent) -> void:
if event.is_action_pressed(\"TiltArmUp\"):
Lunabot.tilt_bucket_up()
elif event.is_action_released(\"TiltArmUp\"):
Lunabot.stop_arm()
Lunabot.stop_tilt_bucket()
"
[sub_resource type="GDScript" id="GDScript_2xh7u"]
Expand All @@ -115,14 +121,14 @@ func _on_pressed() -> void:


func _on_button_up() -> void:
Lunabot.stop_arm()
Lunabot.stop_tilt_bucket()


func _input(event: InputEvent) -> void:
if event.is_action_pressed(\"TiltArmDown\"):
Lunabot.tilt_bucket_down()
elif event.is_action_released(\"TiltArmDown\"):
Lunabot.stop_arm()
Lunabot.stop_tilt_bucket()
"
[sub_resource type="GDScript" id="GDScript_dn1oa"]
Expand All @@ -134,14 +140,14 @@ func _on_pressed() -> void:


func _on_button_up() -> void:
Lunabot.stop_arm()
Lunabot.stop_lift_arm()


func _input(event: InputEvent) -> void:
if event.is_action_pressed(\"LiftArm\"):
Lunabot.lift_arm()
elif event.is_action_released(\"LiftArm\"):
Lunabot.stop_arm()
Lunabot.stop_lift_arm()
"
[sub_resource type="GDScript" id="GDScript_qbnfj"]
Expand All @@ -153,14 +159,14 @@ func _on_pressed() -> void:


func _on_button_up() -> void:
Lunabot.stop_arm()
Lunabot.stop_lift_arm()


func _input(event: InputEvent) -> void:
if event.is_action_pressed(\"LowerArm\"):
Lunabot.lower_arm()
elif event.is_action_released(\"LowerArm\"):
Lunabot.stop_arm()
Lunabot.stop_lift_arm()
"
[sub_resource type="GDScript" id="GDScript_amk46"]
Expand Down
14 changes: 12 additions & 2 deletions lunabotics/lunabase/project.godot
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,12 @@ DriveBackward={
}
SteerLeft={
"deadzone": 0.5,
"events": [Object(InputEventJoypadMotion,"resource_local_to_scene":false,"resource_name":"","device":-1,"axis":2,"axis_value":-1.0,"script":null)
"events": [Object(InputEventJoypadMotion,"resource_local_to_scene":false,"resource_name":"","device":-1,"axis":0,"axis_value":-1.0,"script":null)
]
}
SteerRight={
"deadzone": 0.5,
"events": [Object(InputEventJoypadMotion,"resource_local_to_scene":false,"resource_name":"","device":-1,"axis":2,"axis_value":1.0,"script":null)
"events": [Object(InputEventJoypadMotion,"resource_local_to_scene":false,"resource_name":"","device":-1,"axis":0,"axis_value":1.0,"script":null)
]
}
WalkForward={
Expand Down Expand Up @@ -114,6 +114,16 @@ MainMenu={
"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":true,"ctrl_pressed":true,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":81,"key_label":0,"unicode":0,"echo":false,"script":null)
]
}
NextCamera={
"deadzone": 0.5,
"events": [Object(InputEventJoypadButton,"resource_local_to_scene":false,"resource_name":"","device":-1,"button_index":14,"pressure":0.0,"pressed":false,"script":null)
]
}
PreviousCamera={
"deadzone": 0.5,
"events": [Object(InputEventJoypadButton,"resource_local_to_scene":false,"resource_name":"","device":-1,"button_index":13,"pressure":0.0,"pressed":false,"script":null)
]
}

[rendering]

Expand Down
2 changes: 1 addition & 1 deletion lunabotics/lunabot/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ edition = "2021"
[dependencies]
unros = { workspace = true }
camera = { workspace = true }
localization = { workspace = true }
# localization = { workspace = true }
apriltag = { workspace = true }
networking = { workspace = true }
rig = { workspace = true }
Expand Down
32 changes: 18 additions & 14 deletions lunabotics/lunabot/src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@ use std::sync::{
// use apriltag::{AprilTagDetector, PoseObservation};
use camera::discover_all_cameras;
use fxhash::FxBuildHasher;
use localization::{
engines::window::{DefaultWindowConfig, WindowLocalizer},
Localizer,
};
// use localization::{
// engines::window::{DefaultWindowConfig, WindowLocalizer},
// Localizer,
// };
use rig::Robot;
use telemetry::Telemetry;
use unros::{
Expand Down Expand Up @@ -80,21 +80,25 @@ async fn main(context: MainRuntimeContext) -> anyhow::Result<()> {

match serial::connect_to_serial() {
Ok((arms, drive)) => {
telemetry
.steering_pub()
.accept_subscription(drive.get_steering_sub());

telemetry.arm_pub().accept_subscription(arms.get_arm_sub());
drive.spawn(context.make_context("drive"));
arms.spawn(context.make_context("arms"));
if let Some(drive) = drive {
telemetry
.steering_pub()
.accept_subscription(drive.get_steering_sub());
drive.spawn(context.make_context("drive"));
}

if let Some(arms) = arms {
telemetry.arm_pub().accept_subscription(arms.get_arm_sub());
arms.spawn(context.make_context("arms"));
}
}
Err(e) => {
error!("{e}");
}
}

let localizer: Localizer<f32, WindowLocalizer<f32, _, _, _, _>> =
Localizer::new(robot_base, DefaultWindowConfig::default());
// let localizer: Localizer<f32, WindowLocalizer<f32, _, _, _, _>> =
// Localizer::new(robot_base, DefaultWindowConfig::default());

// let mut apriltag = AprilTagDetector::new(640.0, 1280, 720, camera_element.get_ref());
// apriltag.add_tag(Default::default(), Default::default(), 0.134, 0);
Expand Down Expand Up @@ -134,7 +138,7 @@ async fn main(context: MainRuntimeContext) -> anyhow::Result<()> {
// .msg_received_pub()
// .accept_subscription(localizer.create_imu_sub().set_name("imu01"));

localizer.spawn(context.make_context("localizer"));
// localizer.spawn(context.make_context("localizer"));
telemetry.spawn(context.make_context("telemetry"));

context.wait_for_exit().await;
Expand Down
59 changes: 32 additions & 27 deletions lunabotics/lunabot/src/serial.rs
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
use unros::anyhow;
use unros::log::error;

use crate::{actuators::Arms, drive::Drive};
use std::fs::{self, DirEntry};
use std::process::Command;

pub fn connect_to_serial() -> anyhow::Result<(Arms, Drive)> {
pub fn connect_to_serial() -> anyhow::Result<(Option<Arms>, Option<Drive>)> {
let dev_directory = fs::read_dir("/dev")?;
let acm_devices: Vec<DirEntry> = dev_directory
.filter_map(|entry| {
Expand All @@ -31,16 +32,8 @@ pub fn connect_to_serial() -> anyhow::Result<(Arms, Drive)> {
return Err(anyhow::anyhow!("No ttyACM devices found"));
}

if acm_devices.len() != 4 {
return Err(anyhow::anyhow!(
"Expected 4 ttyACM devices, got {}",
acm_devices.len()
));
}

let mut micro_python_paths = [None, None];
let mut micro_python_paths = Vec::with_capacity(2);
let mut vesc_paths = Vec::with_capacity(2);
let mut micro_py_count = 0usize;
for entry in &acm_devices {
let path = entry.path();
let output = Command::new("udevadm")
Expand All @@ -52,33 +45,45 @@ pub fn connect_to_serial() -> anyhow::Result<(Arms, Drive)> {
.output()?;
let stdout = String::from_utf8_lossy(&output.stdout);
if stdout.contains("MicroPython") {
if micro_py_count >= 2 {
if micro_python_paths.len() >= 2 {
return Err(anyhow::anyhow!("More than two MicroPython devices found"));
}
micro_python_paths[micro_py_count] = Some(path);
micro_py_count += 1;
micro_python_paths.push(path);
} else if vesc_paths.len() >= 2 {
return Err(anyhow::anyhow!("More than two VESC devices found"));
} else {
vesc_paths.push(path);
}
}

if micro_py_count < 2 {
return Err(anyhow::anyhow!(
"Expected 2 MicroPython devices, got {}",
micro_py_count
let mut arms = None;

if micro_python_paths.len() < 2 {
arms = Some(Arms::new(
micro_python_paths[0].to_string_lossy(),
micro_python_paths[1].to_string_lossy(),
));
}

Ok((
Arms::new(
micro_python_paths[0].take().unwrap().to_string_lossy(),
micro_python_paths[1].take().unwrap().to_string_lossy(),
),
Drive::new(
vesc_paths.pop().unwrap().to_string_lossy(),
vesc_paths.pop().unwrap().to_string_lossy(),
)?,
))
let mut drive = None;

if vesc_paths.len() < 2 {
match Drive::new(
vesc_paths[0].to_string_lossy(),
vesc_paths[1].to_string_lossy(),
) {
Ok(d) => drive = Some(d),
Err(e) => error!("{e}"),
}
}

if arms.is_none() {
error!("Failed to connect to arms");
}

if drive.is_none() {
error!("Failed to connect to drive");
}

Ok((arms, drive))
}

0 comments on commit 21f7361

Please sign in to comment.