-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathsdo_mapping.rs
72 lines (62 loc) · 2.75 KB
/
sdo_mapping.rs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
use std::error::Error;
use etherage::{
EthernetSocket, RawMaster,
Slave, SlaveAddress, CommunicationState,
sdo::{self, Sdo},
mapping::{self, Mapping},
registers::{self, SyncDirection},
};
#[tokio::main]
async fn main() -> Result<(), Box<dyn Error>> {
let master = RawMaster::new(EthernetSocket::new("eno1")?);
println!("create mapping");
let config = mapping::Config::default();
let mapping = Mapping::new(&config);
let mut slave = mapping.slave(1);
let alstatus = slave.register(SyncDirection::Read, registers::al::status);
let mut channel = slave.channel(
sdo::SyncChannel{ direction: SyncDirection::Write, index: 0x1c12, capacity: 10 },
// the memory buffer used for sync channels depend on slaves firmware
// 0x1800 .. 0x1c00,
0x1000 .. 0x1400,
);
let mut pdo = channel.push(sdo::Pdo{ index: 0x1600, fixed: false, capacity: 10});
let control = pdo.push(Sdo::<u16>::complete(0x6040));
let _mode = pdo.push(Sdo::<u8>::complete(0x6060));
let _position = pdo.push(Sdo::<i32>::complete(0x607a));
let mut channel = slave.channel(
sdo::SyncChannel{ direction: SyncDirection::Read, index: 0x1c13, capacity: 10 },
// the memory buffer used for sync channels depend on slaves firmware
// 0x1c00 .. 0x2000,
0x1400 .. 0x1800,
);
let mut pdo = channel.push(sdo::Pdo{ index: 0x1a00, fixed: false, capacity: 10});
let status = pdo.push(Sdo::<u16>::complete(0x6041));
let error = pdo.push(Sdo::<u16>::complete(0x603f));
let position = pdo.push(Sdo::<i32>::complete(0x6064));
drop(slave);
println!("done {:#?}", config);
let allocator = mapping::Allocator::new();
let group = allocator.group(&master, &mapping).await;
println!("group {:#?}", group);
println!("fields {:#?}", (control, status, error, position));
let mut slave = Slave::raw(master.clone(), SlaveAddress::AutoIncremented(0));
slave.switch(CommunicationState::Init).await?;
slave.set_address(1).await?;
slave.init_coe().await?;
slave.switch(CommunicationState::PreOperational).await?;
group.configure(&slave).await?;
slave.switch(CommunicationState::SafeOperational).await?;
slave.switch(CommunicationState::Operational).await?;
for _ in 0 .. 20 {
tokio_timerfd::sleep(std::time::Duration::from_millis(2)).await.unwrap();
let mut group = group.data().await;
group.exchange().await;
println!("received {} {} {}",
group.get(alstatus).state(),
group.get(status),
group.get(position),
);
}
Ok(())
}