Skip to content

Commit d4e68aa

Browse files
committed
minor changes
1 parent 491adba commit d4e68aa

File tree

11 files changed

+124
-92
lines changed

11 files changed

+124
-92
lines changed

examples/sdo_mapping.rs

Lines changed: 3 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,8 @@ async fn main() -> std::io::Result<()> {
3939
let torque = pdo.push(Sdo::<i16>::complete(0x6077));
4040
println!("done {:#?}", config);
4141

42-
let mut allocator = mapping::Allocator::new();
43-
let mut group = allocator.group(&master, &mapping);
42+
let allocator = mapping::Allocator::new();
43+
let group = allocator.group(&master, &mapping);
4444

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

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

69-
// let sdo = Sdo::<u32>::complete(0x1c12);
70-
//
71-
// // test read/write
72-
// let received = slave.coe().await.sdo_read(&sdo, u2::new(1)).await;
73-
// slave.coe().await.sdo_write(&sdo, u2::new(1), received).await;
74-
7570
Ok(())
7671
}
7772

examples/servodrive_run.rs

Lines changed: 60 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@ async fn main() -> std::io::Result<()> {
2323
std::thread::spawn(move || loop {
2424
master.send();
2525
})};
26-
std::thread::sleep(Duration::from_millis(500));
2726

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

50-
let mut allocator = mapping::Allocator::new();
51-
let mut group = tokio::sync::Mutex::new(allocator.group(&master, &mapping));
49+
let allocator = mapping::Allocator::new();
50+
let group = allocator.group(&master, &mapping);
5251

5352
println!("group {:#?}", group);
5453
println!("fields {:#?}", (statusword, controlword));
@@ -59,7 +58,7 @@ async fn main() -> std::io::Result<()> {
5958
slave.init_mailbox().await;
6059
slave.init_coe().await;
6160
slave.switch(CommunicationState::PreOperational).await;
62-
group.get_mut().configure(&slave).await;
61+
group.configure(&slave).await;
6362
slave.switch(CommunicationState::SafeOperational).await;
6463
slave.switch(CommunicationState::Operational).await;
6564

@@ -70,15 +69,15 @@ async fn main() -> std::io::Result<()> {
7069
async {
7170
let mut period = tokio::time::interval(Duration::from_millis(1));
7271
loop {
73-
let mut group = group.lock().await;
72+
let mut group = group.data().await;
7473
period.tick().await;
7574
group.exchange().await;
7675
cycle.notify_waiters();
7776
}
7877
},
7978
async {
8079
let initial = {
81-
let mut group = group.lock().await;
80+
let mut group = group.data().await;
8281

8382
let initial = group.get(current_position);
8483
group.set(target_mode, OperationMode::SynchronousPosition);
@@ -88,17 +87,20 @@ async fn main() -> std::io::Result<()> {
8887
println!("position {}", initial);
8988
initial
9089
};
90+
91+
use bilge::prelude::u2;
92+
println!("power: {:?}", slave.coe().await.sdo_read(&sdo::error, u2::new(0)).await);
9193

9294
println!("switch on");
93-
switch_on(statusword, controlword, &group, &cycle).await;
95+
switch_on(statusword, controlword, error, &group, &cycle).await;
9496

9597
let velocity = 3_000_000;
9698
let increment = 100_000_000;
9799

98100
println!("move forward");
99101
loop {
100102
cycle.notified().await;
101-
let mut group = group.lock().await;
103+
let mut group = group.data().await;
102104

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

114116
let position = group.get(current_position);
115117
if position <= initial {break}
@@ -129,55 +131,57 @@ async fn main() -> std::io::Result<()> {
129131
pub async fn switch_on(
130132
statusword: Field<sdo::StatusWord>,
131133
controlword: Field<sdo::ControlWord>,
132-
group: &tokio::sync::Mutex<Group<'_>>,
134+
error: Field<u16>,
135+
group: &Group<'_>,
133136
cycle: &tokio::sync::Notify,
134137
) {
135-
loop {
136-
cycle.notified().await;
137-
let mut group = group.lock().await;
138-
139-
let status = group.get(statusword);
140-
let mut control = sdo::ControlWord::default();
141-
142-
// state "not ready to switch on"
143-
if ! status.quick_stop() {
144-
// move to "switch on disabled"
145-
control.set_quick_stop(true);
146-
control.set_enable_voltage(true);
147-
}
148-
// state "switch on disabled"
149-
else if status.switch_on_disabled() {
150-
control.set_quick_stop(true);
151-
control.set_enable_voltage(true);
152-
control.set_switch_on(false);
153-
}
154-
// state "ready to switch on"
155-
else if ! status.switched_on() && status.ready_switch_on() {
156-
// move to "switched on"
157-
control.set_quick_stop(true);
158-
control.set_enable_voltage(true);
159-
control.set_switch_on(true);
160-
control.set_enable_operation(false);
161-
}
162-
// state "ready to switch on" or "switched on"
163-
else if ! status.operation_enabled() && (status.ready_switch_on() | status.switched_on()) {
164-
// move to "operation enabled"
165-
control.set_quick_stop(true);
166-
control.set_enable_voltage(true);
167-
control.set_switch_on(true);
168-
control.set_enable_operation(true);
169-
}
170-
// state "fault"
171-
else if status.fault() && ! status.switched_on() {
172-
// move to "switch on disabled"
173-
control.set_reset_fault(true);
174-
}
175-
// we are in the state we wanted !
176-
else if status.operation_enabled() {
177-
return;
178-
}
179-
group.set(controlword, control);
138+
loop {
139+
{
140+
let mut group = group.data().await;
141+
let status = group.get(statusword);
142+
let mut control = sdo::ControlWord::default();
143+
144+
// state "not ready to switch on"
145+
// we are in the state we wanted !
146+
if status.operation_enabled() {
147+
return;
148+
}
149+
// state "fault"
150+
else if status.fault() && ! status.switched_on() {
151+
// move to "switch on disabled"
152+
control.set_reset_fault(true);
153+
}
154+
else if ! status.quick_stop() {
155+
// move to "switch on disabled"
156+
control.set_quick_stop(true);
157+
control.set_enable_voltage(true);
158+
}
159+
// state "switch on disabled"
160+
else if status.switch_on_disabled() {
161+
control.set_quick_stop(true);
162+
control.set_enable_voltage(true);
163+
control.set_switch_on(false);
164+
}
165+
// state "ready to switch on"
166+
else if ! status.switched_on() && status.ready_switch_on() {
167+
// move to "switched on"
168+
control.set_quick_stop(true);
169+
control.set_enable_voltage(true);
170+
control.set_switch_on(true);
171+
control.set_enable_operation(false);
172+
}
173+
// state "ready to switch on" or "switched on"
174+
else if ! status.operation_enabled() && (status.ready_switch_on() | status.switched_on()) {
175+
// move to "operation enabled"
176+
control.set_quick_stop(true);
177+
control.set_enable_voltage(true);
178+
control.set_switch_on(true);
179+
control.set_enable_operation(true);
180+
}
181+
group.set(controlword, control);
182+
println!("switch on {} {} {:#x}", status, control, group.get(error));
183+
}
180184

181-
println!("switch on {} {} {:x}", status, control, u16::from(control));
185+
cycle.notified().await;
182186
}
183187
}

examples/slaves_discovery.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ async fn main() -> std::io::Result<()> {
2222
std::thread::spawn(move || loop {
2323
unsafe {master.get_raw()}.send();
2424
})};
25-
std::thread::sleep(Duration::from_millis(500));
25+
// std::thread::sleep(Duration::from_millis(500));
2626

2727
master.reset_addresses().await;
2828

readme.md

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,10 @@ This crate aims to bring yet a other implementation of an Ethercat master, The [
3939

4040
## non-goals
4141

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

4647
## Current complete feature list
4748

@@ -96,3 +97,16 @@ cargo build --example slaves_discovery
9697
sudo target/debug/examples/slaves_discovery
9798
```
9899

100+
typical output:
101+
102+
```
103+
slave 7: "R88D-1SN01H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
104+
slave 0: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
105+
slave 6: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.01" software "V1.04.00"
106+
slave 3: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
107+
slave 5: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
108+
slave 4: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
109+
slave 1: "R88D-1SN02H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.00" software "V1.02.00"
110+
slave 2: "R88D-1SN04H-ECT" - ecat type 17 rev 0 build 3 - hardware "V1.01" software "V1.04.00"
111+
```
112+

src/can.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -469,7 +469,7 @@ pub enum SdoAbortCode {
469469
UnsupportedCommand = 0x05_04_00_01,
470470
/// Out of memory
471471
OufOfMemory = 0x05_04_00_05,
472-
/// Unsupported access to an object
472+
/// Unsupported access to an object, this is raised when trying to access a complete SDO when complete SDO access is not supported
473473
UnsupportedAccess = 0x06_01_00_00,
474474
/// Attempt to read to a write only object
475475
WriteOnly = 0x06_01_00_01,

src/lib.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ pub use crate::socket::*;
6767
pub use crate::rawmaster::{RawMaster, SlaveAddress};
6868
pub use crate::master::Master;
6969
pub use crate::slave::{Slave, CommunicationState};
70-
pub use crate::mapping::{Mapping, Group};
70+
pub use crate::mapping::{Mapping, Group, Config};
7171

7272

7373
use std::sync::Arc;

src/mailbox.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ impl<'b> Mailbox<'b> {
100100
101101
- 0 is lowest priority, 3 is highest
102102
*/
103-
pub async fn read<'a>(&mut self, ty: MailboxType, priority: u2, data: &'a mut [u8]) -> &'a [u8] {
103+
pub async fn read<'a>(&mut self, ty: MailboxType, _priority: u2, data: &'a mut [u8]) -> &'a [u8] {
104104
let mailbox_control = registers::sync_manager::interface.mailbox_read();
105105
let mut allocated = [0; MAILBOX_MAX_SIZE];
106106

src/mapping.rs

Lines changed: 30 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -138,9 +138,11 @@ impl Allocator {
138138
new
139139
});
140140
}
141-
// create
141+
// create initial buffers
142+
let mut buffer = mapping.default.borrow().clone();
143+
buffer.extend((buffer.len() .. size as usize).map(|_| 0));
144+
// create group
142145
Group {
143-
master,
144146
allocator: self,
145147
allocated: slot.size,
146148
offset: slot.position,
@@ -150,9 +152,8 @@ impl Allocator {
150152
data: tokio::sync::Mutex::new(GroupData {
151153
master,
152154
offset: slot.position,
153-
size,
154-
read: vec![0; size as usize],
155-
write: vec![0; size as usize],
155+
read: buffer.clone(),
156+
write: buffer,
156157
}),
157158
}
158159
}
@@ -212,10 +213,12 @@ impl fmt::Debug for Allocator {
212213
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.
213214
*/
214215
pub struct Group<'a> {
215-
master: &'a RawMaster,
216216
allocator: &'a Allocator,
217+
/// byte size of the allocated region of the logical memory
217218
allocated: u32,
219+
/// byte offset of this data group in the logical memory
218220
offset: u32,
221+
/// byte size of this data group in the logical memory
219222
size: u32,
220223

221224
/// configuration per slave
@@ -226,8 +229,6 @@ pub struct GroupData<'a> {
226229
master: &'a RawMaster,
227230
/// byte offset of this data group in the logical memory
228231
offset: u32,
229-
/// byte size of this data group in the logical memory
230-
size: u32,
231232
/// data duplex: data to read from slave
232233
read: Vec<u8>,
233234
/// data duplex: data to write to slave
@@ -445,10 +446,15 @@ impl Config {
445446
pub struct Mapping<'a> {
446447
config: &'a Config,
447448
offset: RefCell<u32>,
449+
default: RefCell<Vec<u8>>,
448450
}
449451
impl<'a> Mapping<'a> {
450452
pub fn new(config: &'a Config) -> Self {
451-
Self { config, offset: RefCell::new(0) }
453+
Self {
454+
config,
455+
offset: RefCell::new(0),
456+
default: RefCell::new(Vec::new()),
457+
}
452458
}
453459
/// reference to the devices configuration actually worked on by this mapping
454460
pub fn config(&self) -> &'a Config {
@@ -530,6 +536,12 @@ impl<'a> MappingSlave<'a> {
530536
*offset += length as u32;
531537
inserted
532538
}
539+
fn default<T: PduData>(&self, field: Field<T>, value: T) {
540+
let mut default = self.mapping.default.borrow_mut();
541+
let range = default.len() .. field.byte + field.len;
542+
default.extend(range.map(|_| 0));
543+
field.set(&mut default, value);
544+
}
533545
/// increment the value offset with the reserved additional size
534546
/// this is typically for counting the reserved size of channels triple buffers
535547
fn finish(&mut self) {
@@ -624,5 +636,14 @@ impl<'a> MappingPdo<'a> {
624636
self.slave.additional += 2*len as u16;
625637
Field::new(self.slave.insert(self.direction, len, None), len)
626638
}
639+
/**
640+
same as [Self::push] but also set an initial value for this SDO in the group buffer.
641+
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.
642+
*/
643+
pub fn set<T: PduData>(&mut self, sdo: Sdo<T>, initial: T) -> Field<T> {
644+
let offset = self.push(sdo);
645+
self.slave.default(offset, initial);
646+
offset
647+
}
627648
}
628649

src/rawmaster.rs

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,7 @@
44
It wraps an ethercat socket to schedule, send and receive ethercat frames containing data or commands.
55
*/
66

7-
use std::{
8-
time::Instant,
9-
sync::{Mutex, Condvar},
10-
};
7+
use std::sync::{Mutex, Condvar};
118
use core::{
129
ops::DerefMut,
1310
time::Duration,
@@ -350,7 +347,7 @@ impl RawMaster {
350347
}
351348

352349
/// 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
353-
fn flush(&self) {
350+
pub fn flush(&self) {
354351
let mut state = self.pdu_state.lock().unwrap();
355352
state.ready = true;
356353
self.sendable.notify_one();

0 commit comments

Comments
 (0)