Skip to content

Commit

Permalink
minor changes
Browse files Browse the repository at this point in the history
  • Loading branch information
jimy-byerley committed Jul 7, 2023
1 parent 491adba commit d4e68aa
Show file tree
Hide file tree
Showing 11 changed files with 124 additions and 92 deletions.
11 changes: 3 additions & 8 deletions examples/sdo_mapping.rs
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ async fn main() -> std::io::Result<()> {
let torque = pdo.push(Sdo::<i16>::complete(0x6077));
println!("done {:#?}", config);

let mut allocator = mapping::Allocator::new();
let mut group = allocator.group(&master, &mapping);
let allocator = mapping::Allocator::new();
let group = allocator.group(&master, &mapping);

println!("group {:#?}", group);
println!("fields {:#?}", (control, status, error, position));
Expand All @@ -56,6 +56,7 @@ async fn main() -> std::io::Result<()> {
slave.switch(CommunicationState::Operational).await;

for _ in 0 .. 20 {
let mut group = group.data().await;
group.exchange().await;
println!("received {:?} {} {} {} {}",
group.get(restatus),
Expand All @@ -66,12 +67,6 @@ async fn main() -> std::io::Result<()> {
);
}

// let sdo = Sdo::<u32>::complete(0x1c12);
//
// // test read/write
// let received = slave.coe().await.sdo_read(&sdo, u2::new(1)).await;
// slave.coe().await.sdo_write(&sdo, u2::new(1), received).await;

Ok(())
}

116 changes: 60 additions & 56 deletions examples/servodrive_run.rs
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ async fn main() -> std::io::Result<()> {
std::thread::spawn(move || loop {
master.send();
})};
std::thread::sleep(Duration::from_millis(500));

println!("create mapping");
let config = mapping::Config::default();
Expand All @@ -47,8 +46,8 @@ async fn main() -> std::io::Result<()> {
let _current_torque = pdo.push(sdo::cia402::current::torque);
println!("done {:#?}", config);

let mut allocator = mapping::Allocator::new();
let mut group = tokio::sync::Mutex::new(allocator.group(&master, &mapping));
let allocator = mapping::Allocator::new();
let group = allocator.group(&master, &mapping);

println!("group {:#?}", group);
println!("fields {:#?}", (statusword, controlword));
Expand All @@ -59,7 +58,7 @@ async fn main() -> std::io::Result<()> {
slave.init_mailbox().await;
slave.init_coe().await;
slave.switch(CommunicationState::PreOperational).await;
group.get_mut().configure(&slave).await;
group.configure(&slave).await;
slave.switch(CommunicationState::SafeOperational).await;
slave.switch(CommunicationState::Operational).await;

Expand All @@ -70,15 +69,15 @@ async fn main() -> std::io::Result<()> {
async {
let mut period = tokio::time::interval(Duration::from_millis(1));
loop {
let mut group = group.lock().await;
let mut group = group.data().await;
period.tick().await;
group.exchange().await;
cycle.notify_waiters();
}
},
async {
let initial = {
let mut group = group.lock().await;
let mut group = group.data().await;

let initial = group.get(current_position);
group.set(target_mode, OperationMode::SynchronousPosition);
Expand All @@ -88,17 +87,20 @@ async fn main() -> std::io::Result<()> {
println!("position {}", initial);
initial
};

use bilge::prelude::u2;
println!("power: {:?}", slave.coe().await.sdo_read(&sdo::error, u2::new(0)).await);

println!("switch on");
switch_on(statusword, controlword, &group, &cycle).await;
switch_on(statusword, controlword, error, &group, &cycle).await;

let velocity = 3_000_000;
let increment = 100_000_000;

println!("move forward");
loop {
cycle.notified().await;
let mut group = group.lock().await;
let mut group = group.data().await;

let position = group.get(current_position);
if position >= initial + increment {break}
Expand All @@ -109,7 +111,7 @@ async fn main() -> std::io::Result<()> {
println!("move backward");
loop {
cycle.notified().await;
let mut group = group.lock().await;
let mut group = group.data().await;

let position = group.get(current_position);
if position <= initial {break}
Expand All @@ -129,55 +131,57 @@ async fn main() -> std::io::Result<()> {
pub async fn switch_on(
statusword: Field<sdo::StatusWord>,
controlword: Field<sdo::ControlWord>,
group: &tokio::sync::Mutex<Group<'_>>,
error: Field<u16>,
group: &Group<'_>,
cycle: &tokio::sync::Notify,
) {
loop {
cycle.notified().await;
let mut group = group.lock().await;

let status = group.get(statusword);
let mut control = sdo::ControlWord::default();

// state "not ready to switch on"
if ! status.quick_stop() {
// move to "switch on disabled"
control.set_quick_stop(true);
control.set_enable_voltage(true);
}
// state "switch on disabled"
else if status.switch_on_disabled() {
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(false);
}
// state "ready to switch on"
else if ! status.switched_on() && status.ready_switch_on() {
// move to "switched on"
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(true);
control.set_enable_operation(false);
}
// state "ready to switch on" or "switched on"
else if ! status.operation_enabled() && (status.ready_switch_on() | status.switched_on()) {
// move to "operation enabled"
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(true);
control.set_enable_operation(true);
}
// state "fault"
else if status.fault() && ! status.switched_on() {
// move to "switch on disabled"
control.set_reset_fault(true);
}
// we are in the state we wanted !
else if status.operation_enabled() {
return;
}
group.set(controlword, control);
loop {
{
let mut group = group.data().await;
let status = group.get(statusword);
let mut control = sdo::ControlWord::default();

// state "not ready to switch on"
// we are in the state we wanted !
if status.operation_enabled() {
return;
}
// state "fault"
else if status.fault() && ! status.switched_on() {
// move to "switch on disabled"
control.set_reset_fault(true);
}
else if ! status.quick_stop() {
// move to "switch on disabled"
control.set_quick_stop(true);
control.set_enable_voltage(true);
}
// state "switch on disabled"
else if status.switch_on_disabled() {
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(false);
}
// state "ready to switch on"
else if ! status.switched_on() && status.ready_switch_on() {
// move to "switched on"
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(true);
control.set_enable_operation(false);
}
// state "ready to switch on" or "switched on"
else if ! status.operation_enabled() && (status.ready_switch_on() | status.switched_on()) {
// move to "operation enabled"
control.set_quick_stop(true);
control.set_enable_voltage(true);
control.set_switch_on(true);
control.set_enable_operation(true);
}
group.set(controlword, control);
println!("switch on {} {} {:#x}", status, control, group.get(error));
}

println!("switch on {} {} {:x}", status, control, u16::from(control));
cycle.notified().await;
}
}
2 changes: 1 addition & 1 deletion examples/slaves_discovery.rs
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ async fn main() -> std::io::Result<()> {
std::thread::spawn(move || loop {
unsafe {master.get_raw()}.send();
})};
std::thread::sleep(Duration::from_millis(500));
// std::thread::sleep(Duration::from_millis(500));

master.reset_addresses().await;

Expand Down
16 changes: 15 additions & 1 deletion readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,10 @@ This crate aims to bring yet a other implementation of an Ethercat master, The [

## non-goals

- no-std *(atm)*
- no-std *(at the moment)*
- adapt to vendor-specific implementations of ethercat, or to vendor-specific devices
- make abstraction of what the Ethercat protocol really does
- fit the OSI model

## Current complete feature list

Expand Down Expand Up @@ -96,3 +97,16 @@ cargo build --example slaves_discovery
sudo target/debug/examples/slaves_discovery
```

typical output:

```
slave 7: "R88D-1SN01H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 0: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 6: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.01" software "V1.04.00"
slave 3: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 5: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 4: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 1: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
slave 2: "R88D-1SN04H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.01" software "V1.04.00"
```

2 changes: 1 addition & 1 deletion src/can.rs
Original file line number Diff line number Diff line change
Expand Up @@ -469,7 +469,7 @@ pub enum SdoAbortCode {
UnsupportedCommand = 0x05_04_00_01,
/// Out of memory
OufOfMemory = 0x05_04_00_05,
/// Unsupported access to an object
/// Unsupported access to an object, this is raised when trying to access a complete SDO when complete SDO access is not supported
UnsupportedAccess = 0x06_01_00_00,
/// Attempt to read to a write only object
WriteOnly = 0x06_01_00_01,
Expand Down
2 changes: 1 addition & 1 deletion src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ pub use crate::socket::*;
pub use crate::rawmaster::{RawMaster, SlaveAddress};
pub use crate::master::Master;
pub use crate::slave::{Slave, CommunicationState};
pub use crate::mapping::{Mapping, Group};
pub use crate::mapping::{Mapping, Group, Config};


use std::sync::Arc;
Expand Down
2 changes: 1 addition & 1 deletion src/mailbox.rs
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ impl<'b> Mailbox<'b> {
- 0 is lowest priority, 3 is highest
*/
pub async fn read<'a>(&mut self, ty: MailboxType, priority: u2, data: &'a mut [u8]) -> &'a [u8] {
pub async fn read<'a>(&mut self, ty: MailboxType, _priority: u2, data: &'a mut [u8]) -> &'a [u8] {
let mailbox_control = registers::sync_manager::interface.mailbox_read();
let mut allocated = [0; MAILBOX_MAX_SIZE];

Expand Down
39 changes: 30 additions & 9 deletions src/mapping.rs
Original file line number Diff line number Diff line change
Expand Up @@ -138,9 +138,11 @@ impl Allocator {
new
});
}
// create
// create initial buffers
let mut buffer = mapping.default.borrow().clone();
buffer.extend((buffer.len() .. size as usize).map(|_| 0));
// create group
Group {
master,
allocator: self,
allocated: slot.size,
offset: slot.position,
Expand All @@ -150,9 +152,8 @@ impl Allocator {
data: tokio::sync::Mutex::new(GroupData {
master,
offset: slot.position,
size,
read: vec![0; size as usize],
write: vec![0; size as usize],
read: buffer.clone(),
write: buffer,
}),
}
}
Expand Down Expand Up @@ -212,10 +213,12 @@ impl fmt::Debug for Allocator {
This can typically be though to as a group of slaves, except this only manage logical memory data without any assumption on its content. It is hence unable to perform any multi-slave exception management.
*/
pub struct Group<'a> {
master: &'a RawMaster,
allocator: &'a Allocator,
/// byte size of the allocated region of the logical memory
allocated: u32,
/// byte offset of this data group in the logical memory
offset: u32,
/// byte size of this data group in the logical memory
size: u32,

/// configuration per slave
Expand All @@ -226,8 +229,6 @@ pub struct GroupData<'a> {
master: &'a RawMaster,
/// byte offset of this data group in the logical memory
offset: u32,
/// byte size of this data group in the logical memory
size: u32,
/// data duplex: data to read from slave
read: Vec<u8>,
/// data duplex: data to write to slave
Expand Down Expand Up @@ -445,10 +446,15 @@ impl Config {
pub struct Mapping<'a> {
config: &'a Config,
offset: RefCell<u32>,
default: RefCell<Vec<u8>>,
}
impl<'a> Mapping<'a> {
pub fn new(config: &'a Config) -> Self {
Self { config, offset: RefCell::new(0) }
Self {
config,
offset: RefCell::new(0),
default: RefCell::new(Vec::new()),
}
}
/// reference to the devices configuration actually worked on by this mapping
pub fn config(&self) -> &'a Config {
Expand Down Expand Up @@ -530,6 +536,12 @@ impl<'a> MappingSlave<'a> {
*offset += length as u32;
inserted
}
fn default<T: PduData>(&self, field: Field<T>, value: T) {
let mut default = self.mapping.default.borrow_mut();
let range = default.len() .. field.byte + field.len;
default.extend(range.map(|_| 0));
field.set(&mut default, value);
}
/// increment the value offset with the reserved additional size
/// this is typically for counting the reserved size of channels triple buffers
fn finish(&mut self) {
Expand Down Expand Up @@ -624,5 +636,14 @@ impl<'a> MappingPdo<'a> {
self.slave.additional += 2*len as u16;
Field::new(self.slave.insert(self.direction, len, None), len)
}
/**
same as [Self::push] but also set an initial value for this SDO in the group buffer.
This is useful when using a PDO that has more fields than the only desired ones, so we can set them a value and forget them.
*/
pub fn set<T: PduData>(&mut self, sdo: Sdo<T>, initial: T) -> Field<T> {
let offset = self.push(sdo);
self.slave.default(offset, initial);
offset
}
}

7 changes: 2 additions & 5 deletions src/rawmaster.rs
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,7 @@
It wraps an ethercat socket to schedule, send and receive ethercat frames containing data or commands.
*/

use std::{
time::Instant,
sync::{Mutex, Condvar},
};
use std::sync::{Mutex, Condvar};
use core::{
ops::DerefMut,
time::Duration,
Expand Down Expand Up @@ -350,7 +347,7 @@ impl RawMaster {
}

/// trigger sending the buffered PDUs, they will be sent as soon as possible by [Self::send] instead of waiting for the frame to be full or for the timeout
fn flush(&self) {
pub fn flush(&self) {
let mut state = self.pdu_state.lock().unwrap();
state.ready = true;
self.sendable.notify_one();
Expand Down
Loading

0 comments on commit d4e68aa

Please sign in to comment.