forked from RobotLocomotion/drake-franka-driver
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathvalid_shared_memory_patch.diff
More file actions
55 lines (49 loc) · 2.02 KB
/
valid_shared_memory_patch.diff
File metadata and controls
55 lines (49 loc) · 2.02 KB
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
diff --git a/shared_memory.hpp b/shared_memory.hpp
--- a/shared_memory.hpp
+++ b/shared_memory.hpp
@@ struct SharedMemoryData {
typedef bip::allocator<double, bip::managed_shared_memory::segment_manager> ShmemAllocator;
- typedef bip::vector<double, ShmemAllocator> SharedVector;
+ typedef bip::vector<double, ShmemAllocator> SharedVector;
SharedMemoryData(const ShmemAllocator& alloc)
- : data(alloc), ee_wrench(alloc),data_ready(false) {}
+ : data(alloc), ee_wrench(alloc), data_ready(false) {}
bip::interprocess_mutex mutex;
bip::interprocess_condition cond_var;
bool data_ready;
SharedVector data;
- ShmemVector ee_wrench;
+ SharedVector ee_wrench;
};
diff --git a/franka_driver.cc b/franka_driver.cc
--- a/franka_driver.cc
+++ b/franka_driver.cc
@@ class PandaDriver {
+ // Shared memory interface
+ bip::managed_shared_memory shm_segment_;
+ SharedMemoryData* shm_;
@@ PandaDriver::PandaDriver(...)
: robot_(robot_ip_address, franka::RealtimeConfig::kIgnore),
model_(robot_.loadModel()),
lcm_(lcm_url),
lcm_command_channel_(lcm_command_channel),
lcm_status_channel_(lcm_status_channel),
latch_(latch),
expire_usec_(expire_usec),
joint_torque_limit_(joint_torque_limit),
cartesian_force_limit_(cartesian_force_limit),
remove_gravity_compensation_(remove_gravity_compensation),
- plant_(std::move(plant)) {
+ plant_(std::move(plant)),
+ shm_segment_(bip::open_only, "MySharedMemory"),
+ shm_(shm_segment_.find<SharedMemoryData>("SharedData").first) {
@@ void PublishRobotState(const franka::RobotState& state) {
+ // Publish end-effector wrench to shared memory
+ std::array<double, 6> wrench_array = state.O_F_ext_hat_K;
+ {
+ bip::scoped_lock<bip::interprocess_mutex> lock(shm_->mutex);
+ shm_->ee_wrench.clear();
+ shm_->ee_wrench.insert(shm_->ee_wrench.end(), wrench_array.begin(), wrench_array.end());
+ shm_->data_ready = true;
+ shm_->cond_var.notify_one();
+ }