system_bolt.cpp 21 KB
Newer Older
Paul Rouanet's avatar
Paul Rouanet committed
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
// Copyright 2021 ros2_control Development Team
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "system_bolt.hpp"

#include <chrono>
#include <cmath>
#include <limits>
#include <memory>
#include <vector>
#include <string>

#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"

/*Connection to ODRI for read sensors and write commands*/
#include "odri_control_interface/utils.hpp"
#include "odri_control_interface/imu.hpp"



using namespace odri_control_interface;
34
using namespace Eigen;
35
36
using namespace semantic_components;

Paul Rouanet's avatar
Paul Rouanet committed
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51


#include <iostream>
#include <stdexcept>



namespace ros2_control_bolt
{

/* Code issue from demo_bolt_actuator_control.cpp (ODRI)*/

Eigen::Vector6d desired_joint_position = Eigen::Vector6d::Zero();
Eigen::Vector6d desired_torque = Eigen::Vector6d::Zero();

Paul Rouanet's avatar
Paul Rouanet committed
52

53
return_type SystemBoltHardware::init_robot(const hardware_interface::HardwareInfo & info)
Paul Rouanet's avatar
Paul Rouanet committed
54
{
Paul Rouanet's avatar
Paul Rouanet committed
55
56
  // Get the ethernet interface to discuss with the ODRI master board
  eth_interface_ = info_.hardware_parameters.at("eth_interface");
Paul Rouanet's avatar
Paul Rouanet committed
57
58
59


  
Paul Rouanet's avatar
Paul Rouanet committed
60
61
62
  /*Définir le robot (ODRI) à partir des variables de l'URDF*/

  // Define board (ODRI)
Paul Rouanet's avatar
Paul Rouanet committed
63
  auto main_board_ptr_ = std::make_shared<MasterBoardInterface>(eth_interface_);
Paul Rouanet's avatar
Paul Rouanet committed
64
65

  // Define joints (ODRI)
Paul Rouanet's avatar
Paul Rouanet committed
66
  
Paul Rouanet's avatar
Paul Rouanet committed
67
  for (const hardware_interface::ComponentInfo & joint : info.joints) {
68
69
70
71
72
73
74
75
76
77
    // Motor numbers
    motor_numbers_[joint_name_to_motor_nb_[joint.name]] = stoi(joint.parameters.at("motor_number"));
    // Reversed polarities
    if (joint.parameters.at("motor_reversed_polarity") == "true"){
      motor_reversed_polarities_[joint_name_to_motor_nb_[joint.name]] = true;
    }
    else {
      motor_reversed_polarities_[joint_name_to_motor_nb_[joint.name]] = false;
    }
    // Joint parameters
Paul Rouanet's avatar
Paul Rouanet committed
78
79
    joint_lower_limits_[joint_name_to_motor_nb_[joint.name]] = stod(joint.command_interfaces[0].min);   //Modif d'après lecture des capteurs (demo bolt)
    joint_upper_limits_[joint_name_to_motor_nb_[joint.name]] = stod(joint.command_interfaces[0].max);   //Modif d'après lecture des capteurs (demo bolt)
80
81
82
83
84
85
    
    motor_constants_ = stod(joint.parameters.at("motor_constant"));
    gear_ratios_ = stod(joint.parameters.at("gear_ratio"));
    max_currents_ = stod(joint.parameters.at("max_current"));
    max_joint_velocities_ = stod(joint.parameters.at("max_joint_velocity"));
    safety_damping_ = stod(joint.parameters.at("safety_damping"));
Paul Rouanet's avatar
Paul Rouanet committed
86
87
88
  }

  auto joints = std::make_shared<JointModules>(main_board_ptr_,
Paul Rouanet's avatar
Paul Rouanet committed
89
                                               motor_numbers_,
Paul Rouanet's avatar
Paul Rouanet committed
90
91
92
93
94
95
96
97
                                               motor_constants_,
                                               gear_ratios_,
                                               max_currents_,
                                               motor_reversed_polarities_,
                                               joint_lower_limits_,
                                               joint_upper_limits_,
                                               max_joint_velocities_,
                                               safety_damping_);
Paul Rouanet's avatar
Paul Rouanet committed
98
99

  // Define the IMU (ODRI).
Paul Rouanet's avatar
Paul Rouanet committed
100
101
  rotate_vector_ << 1, 2, 3;
  orientation_vector_ << 1, 2, 3, 4;
Paul Rouanet's avatar
Paul Rouanet committed
102
  auto imu = std::make_shared<IMU>(
Paul Rouanet's avatar
Paul Rouanet committed
103
      main_board_ptr_, rotate_vector_, orientation_vector_);
Paul Rouanet's avatar
Paul Rouanet committed
104
105
  
  // Define the robot (ODRI).
Paul Rouanet's avatar
Paul Rouanet committed
106
  robot_ = std::make_shared<Robot>(main_board_ptr_, joints, imu);
Paul Rouanet's avatar
Paul Rouanet committed
107

Paul Rouanet's avatar
Paul Rouanet committed
108
  //Definition of Kp and Kd :
109
  /*std::cout << "Enter Kp value (3 in casual use) : ";
Paul Rouanet's avatar
Paul Rouanet committed
110
111
  std::cin >> kp_;
  std::cout << "Kp = " << kp_;
Paul Rouanet's avatar
Paul Rouanet committed
112
  std::cout << "\n" << std::endl;
Paul Rouanet's avatar
Paul Rouanet committed
113

Paul Rouanet's avatar
Paul Rouanet committed
114
  std::cout << "Enter Kd value (0.05 in casual use) : ";
Paul Rouanet's avatar
Paul Rouanet committed
115
116
  std::cin >> kd_;
  std::cout << "Kd = " << kd_;
117
  std::cout << "\n" << std::endl;*/
Paul Rouanet's avatar
Paul Rouanet committed
118

Paul Rouanet's avatar
Paul Rouanet committed
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
/*
  for (const hardware_interface::ComponentInfo & joint : info.joints) {
    //Données des joints
    //Sorties (commandes)
    joint.command_interfaces;
    //Entrées (états)
    joint.state_interfaces;
    
  }

  for (const hardware_interface::ComponentInfo & sensor : info.sensors) {
    //Données des capteurs
    //Entrées (états)
    sensor.state_interfaces;
  }

    */

return return_type::OK;
}






Paul Rouanet's avatar
Paul Rouanet committed
145
146
147
148
149
150
151
152

return_type SystemBoltHardware::configure(
  const hardware_interface::HardwareInfo & info)
{
  if (configure_default(info) != return_type::OK) {
    return return_type::ERROR;
  }

Paul Rouanet's avatar
Paul Rouanet committed
153

Paul Rouanet's avatar
Paul Rouanet committed
154
155
156
157
  hw_start_sec_ = stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
  hw_stop_sec_ = stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
  hw_slowdown_ = stod(info_.hardware_parameters["example_param_hw_slowdown"]);

158
159
160
161
162
163
164
165
166
  //For each sensor.
  for (const hardware_interface::ComponentInfo & sensor : info_.sensors) {
    imu_states_[sensor.name] =
      {std::numeric_limits<Eigen::Vector3d>::quiet_NaN(),
       std::numeric_limits<Eigen::Vector3d>::quiet_NaN(),
       std::numeric_limits<Eigen::Vector3d>::quiet_NaN(),
       std::numeric_limits<Eigen::Vector3d>::quiet_NaN(),
       std::numeric_limits<Eigen::Vector4d>::quiet_NaN()};
  }
Paul Rouanet's avatar
Paul Rouanet committed
167
168
  // For each joint.
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
169
170
171

    // Map joint with motor number
    // (uses at instead of [] because of joint constantness)
Paul Rouanet's avatar
Paul Rouanet committed
172
    joint_name_to_motor_nb_[joint.name] = stoi(joint.parameters.at("motor_number"));
Paul Rouanet's avatar
Paul Rouanet committed
173
174
175
176
    
    // Initialize state of the joint by default to NaN
    // it allows to see which joints are not properly initialized
    // from the real hardware
Paul Rouanet's avatar
Paul Rouanet committed
177
178
179
180
181
182
183
184
185
186
187
188
189
    hw_states_[joint.name] =
      {std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN()};
    hw_commands_[joint.name] =
      {std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN(),
       std::numeric_limits<double>::quiet_NaN()};
    control_mode_[joint.name] = control_mode_t::NO_VALID_MODE;
190

191
     
Paul Rouanet's avatar
Paul Rouanet committed
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264

    // SystemBolt has exactly 5 doubles for the state and
    // 5 doubles for the command interface on each joint
    if (joint.command_interfaces.size() !=
      bolt_list_of_cmd_inter.size())
    {
      RCLCPP_FATAL(
        rclcpp::get_logger("SystemBoltHardware"),
        "Joint '%s' has %d command interfaces found.",             // 5 expected.",
        joint.name.c_str(), joint.command_interfaces.size());
      return return_type::ERROR;
    }

    // For each command interface of the joint
    for (const auto & a_joint_cmd_inter : joint.command_interfaces)
    {
      // Check if the command interface is inside the list
      if (bolt_list_of_cmd_inter.find(a_joint_cmd_inter.name) ==
        bolt_list_of_cmd_inter.end())
      {
        // If not then generate an error message
        RCLCPP_FATAL(
          rclcpp::get_logger("SystemBoltHardware"),
          "Joint '%s' have %s command interfaces found. One of the following values is expected",
          joint.name.c_str(),
          a_joint_cmd_inter.name.c_str());
        for (const auto & a_cmd_inter : bolt_list_of_cmd_inter)
        {
          RCLCPP_FATAL(
            rclcpp::get_logger("SystemBoltHardware"),
            "'%s' expected.", a_cmd_inter.c_str());
        }
        return return_type::ERROR;
      }
    }

    // Check if the state interface list is of the right size
    if (joint.state_interfaces.size() !=
      bolt_list_of_state_inter.size())
    {
      RCLCPP_FATAL(
        rclcpp::get_logger("SystemBoltHardware"),
        "Joint '%s' has %d state interface.",                      // 5 expected.",
        joint.name.c_str(), joint.state_interfaces.size());
      return return_type::ERROR;
    }

    // For each state interface of the joint
    for (const auto & a_joint_state_inter : joint.state_interfaces)
    {
      std::string joint_state_inter_name = a_joint_state_inter.name;

      // Check if the state interface is inside the list
      if (bolt_list_of_state_inter.find(joint_state_inter_name) ==
        bolt_list_of_state_inter.end())
      {
        RCLCPP_FATAL(
          rclcpp::get_logger("SystemBoltHardware"),
          "Joint '%s' have %s state interface. One of the following was expected: ",
          joint.name.c_str(),
          a_joint_state_inter.name.c_str());

        for (const auto & a_state_inter : bolt_list_of_state_inter)
        {
          RCLCPP_FATAL(
            rclcpp::get_logger("SystemBoltHardware"),
            "'%s' expected.", a_state_inter.c_str());
        }
        return return_type::ERROR;
      }
    }
  }

Paul Rouanet's avatar
Paul Rouanet committed
265
266
  

Paul Rouanet's avatar
Paul Rouanet committed
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
  status_ = hardware_interface::status::CONFIGURED;
  RCLCPP_INFO(
    rclcpp::get_logger("SystemBoltHardware"),
    "Finished configure() %p",this);

  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    RCLCPP_INFO(
      rclcpp::get_logger("SystemBoltHardware"),
      "Joint '%s' configuration.",
      joint.name.c_str());
  }
  return return_type::OK;
}


return_type
SystemBoltHardware::prepare_command_mode_switch
(
 const std::vector<std::string> & start_interfaces,
 const std::vector<std::string> & stop_interfaces
 )
{

  RCLCPP_INFO(
    rclcpp::get_logger("SystemBoltHardware"),
    "Going through SystemBoltHardware::prepare_command_mode_switch %d",
    start_interfaces.size());

  // Initialize new modes.
  for (const hardware_interface::ComponentInfo & joint : info_.joints)
    new_modes_[joint.name] = control_mode_t::NO_VALID_MODE;

  /// Check that the key interfaces are coherent
  for (auto & key : start_interfaces) {
    RCLCPP_INFO(rclcpp::get_logger("SystemBoltHardware"),
		"prepare_command_mode_switch %s",key.c_str());

    /// For each joint
    for (const hardware_interface::ComponentInfo & joint : info_.joints) {
      if (key == joint.name + "/" + hardware_interface::HW_IF_POSITION)
	{
	  new_modes_[joint.name]=control_mode_t::POSITION;
	  RCLCPP_INFO(rclcpp::get_logger("SystemBoltHardware"),
		      "%s switch to position",key.c_str());

	}
      if (key == joint.name + "/" + hardware_interface::HW_IF_VELOCITY)
	{
	  new_modes_[joint.name]=control_mode_t::VELOCITY;
	}
      if (key == joint.name + "/" + hardware_interface::HW_IF_EFFORT)
	{
	  new_modes_[joint.name]=control_mode_t::EFFORT;
	}
      if (key == joint.name + "/" + ros2_control_bolt::HW_IF_GAIN_KP)
	{
	  new_modes_[joint.name]=control_mode_t::POS_VEL_EFF_GAINS;
	}
      if (key == joint.name + "/" + ros2_control_bolt::HW_IF_GAIN_KD)
	{
	  new_modes_[joint.name]=control_mode_t::POS_VEL_EFF_GAINS;
	}
    }
  }
  // Stop motion on all relevant joints that are stopping
  for (std::string key : stop_interfaces)
  {
    for (const hardware_interface::ComponentInfo & joint : info_.joints) {
      if (key.find(joint.name) != std::string::npos)
      {
        hw_commands_[joint.name].velocity = 0.0;
        hw_commands_[joint.name].effort = 0.0;
        control_mode_[joint.name] = control_mode_t::NO_VALID_MODE;  // Revert to undefined
      }
    }
  }
  // Set the new command modes
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    if ((control_mode_[joint.name] == control_mode_t::NO_VALID_MODE) &&
	(new_modes_[joint.name]==control_mode_t::NO_VALID_MODE))
    {
      // Something else is using the joint! Abort!
      RCLCPP_ERROR(
        rclcpp::get_logger("SystemBoltHardware"),
	"Joint '%s' has no valid control mode %d %d",
	joint.name.c_str(),
	control_mode_[joint.name],
	new_modes_[joint.name]

      );
      return return_type::ERROR;
    }
    control_mode_[joint.name] = new_modes_[joint.name];
  }

  return return_type::OK;
}

std::vector<hardware_interface::StateInterface>
SystemBoltHardware::export_state_interfaces()
{
  std::vector<hardware_interface::StateInterface> state_interfaces;
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    state_interfaces.emplace_back(
      hardware_interface::StateInterface(
        joint.name, hardware_interface::HW_IF_POSITION,
        &hw_states_[joint.name].position));
    state_interfaces.emplace_back(
      hardware_interface::StateInterface(
        joint.name, hardware_interface::HW_IF_VELOCITY,
        &hw_states_[joint.name].velocity));
    state_interfaces.emplace_back(
      hardware_interface::StateInterface(
        joint.name, hardware_interface::HW_IF_EFFORT,
        &hw_states_[joint.name].effort));
    state_interfaces.emplace_back(
      hardware_interface::StateInterface(
        joint.name, HW_IF_GAIN_KP,
        &hw_states_[joint.name].effort));
    state_interfaces.emplace_back(
      hardware_interface::StateInterface(
        joint.name, HW_IF_GAIN_KD,
        &hw_states_[joint.name].effort));
  }

  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    RCLCPP_INFO(
      rclcpp::get_logger("SystemBoltHardware"),
      "Joint '%s' export_state_interface.",
      joint.name.c_str());
  }

  return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
SystemBoltHardware::export_command_interfaces()
{
  std::vector<hardware_interface::CommandInterface> command_interfaces;
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    command_interfaces.emplace_back(
      hardware_interface::CommandInterface(
        joint.name, hardware_interface::HW_IF_POSITION,
        &hw_commands_[joint.name].position));
    command_interfaces.emplace_back(
      hardware_interface::CommandInterface(
        joint.name, hardware_interface::HW_IF_VELOCITY,
        &hw_commands_[joint.name].velocity));
    command_interfaces.emplace_back(
      hardware_interface::CommandInterface(
        joint.name, hardware_interface::HW_IF_EFFORT,
        &hw_commands_[joint.name].effort));
    command_interfaces.emplace_back(
      hardware_interface::CommandInterface(
        joint.name, HW_IF_GAIN_KP,
        &hw_commands_[joint.name].Kp));
    command_interfaces.emplace_back(
      hardware_interface::CommandInterface(
        joint.name, HW_IF_GAIN_KD,
        &hw_commands_[joint.name].Kd));
  }

  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    RCLCPP_INFO(
      rclcpp::get_logger("SystemBoltHardware"),
      "Joint '%s' export_command_interface.",
      joint.name.c_str());
  }

  return command_interfaces;
}









447
// START
Paul Rouanet's avatar
Paul Rouanet committed
448

449
450
return_type SystemBoltHardware::start()
{
Paul Rouanet's avatar
Paul Rouanet committed
451
  robot_->Start();
Paul Rouanet's avatar
Paul Rouanet committed
452

453
454
455
456
457
458
459
  // set some default values
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    if (std::isnan(hw_states_[joint.name].position)) {
      hw_states_[joint.name] = {0.0, 0.0, 0.0, 0.0, 0.0};
      hw_commands_[joint.name] = {0.0, 0.0, 0.0, 0.0, 0.0};
    }
  }
Paul Rouanet's avatar
Paul Rouanet committed
460

461
  status_ = hardware_interface::status::STARTED;
Paul Rouanet's avatar
Paul Rouanet committed
462

463
/*  RCLCPP_INFO(
Paul Rouanet's avatar
Paul Rouanet committed
464
465
466
    rclcpp::get_logger("SystemBoltHardware"),
    "Starting ...please wait...");

467
//Starting countdown
Paul Rouanet's avatar
Paul Rouanet committed
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
  for (auto i = 0; i <= hw_start_sec_; ++i) {
    rclcpp::sleep_for(std::chrono::seconds(1));
    RCLCPP_INFO(
      rclcpp::get_logger("SystemBoltHardware"),
      "%.1f seconds left...", hw_start_sec_ - i);
  }

  // set some default values
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    if (std::isnan(hw_states_[joint.name].position)) {
      hw_states_[joint.name] = {0.0, 0.0, 0.0, 0.0, 0.0};
      hw_commands_[joint.name] = {0.0, 0.0, 0.0, 0.0, 0.0};
    }
  }

  status_ = hardware_interface::status::STARTED;

  RCLCPP_INFO(
    rclcpp::get_logger("SystemBoltHardware"),
487
488
489
    "System Sucessfully started!");*/


Paul Rouanet's avatar
Paul Rouanet committed
490
491
492
493
494
495
496
497
498
499
500
501
502

  return return_type::OK;
}










Paul Rouanet's avatar
Paul Rouanet committed
503
// STOP
Paul Rouanet's avatar
Paul Rouanet committed
504
505
506

return_type SystemBoltHardware::stop()
{
507
508
509
510
511
512
513
514
515
  // Set 0 values to commands
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    hw_commands_[joint.name] = {0.0, 0.0, 0.0, 0.0, 0.0};
  }




  /*RCLCPP_INFO(
Paul Rouanet's avatar
Paul Rouanet committed
516
517
518
519
520
521
522
523
524
525
526
527
528
529
    rclcpp::get_logger("SystemBoltHardware"),
    "Stopping ...please wait...");

  for (int i = 0; i <= hw_stop_sec_; i++) {
    rclcpp::sleep_for(std::chrono::seconds(1));
    RCLCPP_INFO(
      rclcpp::get_logger("SystemBoltHardware"),
      "%.1f seconds left...", hw_stop_sec_ - i);
  }

  status_ = hardware_interface::status::STOPPED;

  RCLCPP_INFO(
    rclcpp::get_logger("SystemBoltHardware"),
530
    "System sucessfully stopped!");*/
Paul Rouanet's avatar
Paul Rouanet committed
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546

  return return_type::OK;
}







////// READ


hardware_interface::return_type SystemBoltHardware::read()
{

Paul Rouanet's avatar
Paul Rouanet committed
547
  // RCLCPP_INFO(
Paul Rouanet's avatar
Paul Rouanet committed
548
549
550
  //rclcpp::get_logger("SystemBoltHardware"),
  //"Reading...");

Paul Rouanet's avatar
Paul Rouanet committed
551
  // Data acquisition (with ODRI)
Paul Rouanet's avatar
Paul Rouanet committed
552
  robot_->ParseSensorData();
Paul Rouanet's avatar
Paul Rouanet committed
553

Paul Rouanet's avatar
Paul Rouanet committed
554
555
556
  auto sensor_positions = robot_->joints->GetPositions();
  auto sensor_velocities = robot_->joints->GetVelocities();
  auto measured_torques = robot_->joints->GetMeasuredTorques();
557
   
Paul Rouanet's avatar
Paul Rouanet committed
558
559
560
561
562
  auto imu_gyroscope = robot_->imu->GetGyroscope();
  auto imu_accelero = robot_->imu->GetAccelerometer();
  auto imu_linear_acc = robot_->imu->GetLinearAcceleration();
  auto imu_euler = robot_->imu->GetAttitudeEuler();
  auto imu_quater = robot_->imu->GetAttitudeQuaternion();
Paul Rouanet's avatar
Paul Rouanet committed
563

Paul Rouanet's avatar
Paul Rouanet committed
564

Paul Rouanet's avatar
Paul Rouanet committed
565
  // Assignment of sensor data to ros2_control variables (URDF)
Paul Rouanet's avatar
Paul Rouanet committed
566
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
567
568
569
570
571
    hw_states_[joint.name].position = sensor_positions[joint_name_to_motor_nb_[joint.name]];
    hw_states_[joint.name].velocity = sensor_velocities[joint_name_to_motor_nb_[joint.name]];
    hw_states_[joint.name].effort = measured_torques[joint_name_to_motor_nb_[joint.name]];
    hw_states_[joint.name].Kp = kp_;
    hw_states_[joint.name].Kd = kd_;
Paul Rouanet's avatar
Paul Rouanet committed
572
  }
Paul Rouanet's avatar
Paul Rouanet committed
573
574
  
  // Assignment of IMU data (URDF)
575
  // Modif with for loop possible to optimize the code
Paul Rouanet's avatar
Paul Rouanet committed
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
  imu_states_["IMU"].gyro[0] = imu_gyroscope[0];
  imu_states_["IMU"].gyro[1] = imu_gyroscope[1];
  imu_states_["IMU"].gyro[2] = imu_gyroscope[2];

  imu_states_["IMU"].accelero[0] = imu_accelero[0];
  imu_states_["IMU"].accelero[1] = imu_accelero[1];
  imu_states_["IMU"].accelero[2] = imu_accelero[2];

  imu_states_["IMU"].line_acc[0] = imu_linear_acc[0];
  imu_states_["IMU"].line_acc[1] = imu_linear_acc[1];
  imu_states_["IMU"].line_acc[2] = imu_linear_acc[2];

  imu_states_["IMU"].euler[0] = imu_euler[0];
  imu_states_["IMU"].euler[1] = imu_euler[1];
  imu_states_["IMU"].euler[2] = imu_euler[2];

  imu_states_["IMU"].quater[0] = imu_quater[0];
  imu_states_["IMU"].quater[1] = imu_quater[1];
  imu_states_["IMU"].quater[2] = imu_quater[2];
  imu_states_["IMU"].quater[3] = imu_quater[3];
  
597

Paul Rouanet's avatar
Paul Rouanet committed
598
599
600
601
602
603
604
605
606
607
608
609
  // RCLCPP_INFO(
  //rclcpp::get_logger("SystemBoltHardware"),
  //"Joints sucessfully read!");

  return return_type::OK;
}

////// WRITE

hardware_interface::return_type
SystemBoltHardware::write()
{
610
611
612
613
  
  Eigen::Vector6d positions;
  Eigen::Vector6d velocities;
  Eigen::Vector6d torques;
Paul Rouanet's avatar
Paul Rouanet committed
614
615
  Eigen::Vector6d gain_KP;
  Eigen::Vector6d gain_KD;
616
617
618
619
620
621


  double t = 0.0;
  double dt = 0.001;
  std::chrono::time_point<std::chrono::system_clock> last = std::chrono::system_clock::now();

Paul Rouanet's avatar
Paul Rouanet committed
622
  while (!robot_->IsTimeout()) {
623
624
625
626
    if (((std::chrono::duration<double>)(std::chrono::system_clock::now()-last)).count() > 0.001) {
      
      last = std::chrono::system_clock::now();  // last+dt would be better

Paul Rouanet's avatar
Paul Rouanet committed
627
      if (robot_->IsReady()) {
628
629
630
631
632
633
634
        
        // Control law        
        /*positions = ...;
        torques =  ...;*/
        t += dt;
        
        for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
635
636
637
638
639
          positions[joint_name_to_motor_nb_[joint.name]] = hw_commands_[joint.name].position;
          velocities[joint_name_to_motor_nb_[joint.name]] = hw_commands_[joint.name].velocity;
          torques[joint_name_to_motor_nb_[joint.name]] = hw_commands_[joint.name].effort;
          gain_KP[joint_name_to_motor_nb_[joint.name]] = hw_commands_[joint.name].Kp;
          gain_KD[joint_name_to_motor_nb_[joint.name]] = hw_commands_[joint.name].Kd;
Paul Rouanet's avatar
Paul Rouanet committed
640
        }
641

Paul Rouanet's avatar
Paul Rouanet committed
642
643
644
645
646
        robot_->joints->SetDesiredPositions(positions);
        robot_->joints->SetDesiredVelocities(velocities);
        robot_->joints->SetTorques(torques);
        robot_->joints->SetPositionGains(gain_KP);
        robot_->joints->SetVelocityGains(gain_KD);
Paul Rouanet's avatar
Paul Rouanet committed
647
          
648
649
650
651
652
653
      }

      else {
        //Chose à faire si le robot n'est pas Ready
      }
    }
Paul Rouanet's avatar
Paul Rouanet committed
654
    robot_->SendCommand();
655
656
657
  }


Paul Rouanet's avatar
Paul Rouanet committed
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
  // RCLCPP_INFO(
  //   rclcpp::get_logger("SystemBoltHardware"),
  //   "Writing...");
  //  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    // Simulate sending commands to the hardware
    // RCLCPP_INFO(
    //   rclcpp::get_logger("SystemBoltHardware"),
    //   "Got command (%.5f,%.5f,%.5f,%.5f,%.5f) for joint %d!",
    //   hw_commands_[i].position,
    //   hw_commands_[i].velocity,
    //   hw_commands_[i].effort,
    //   hw_commands_[i].Kp,
    //   hw_commands_[i].Kd,
    //   i);
  // }
  // RCLCPP_INFO(
  //   rclcpp::get_logger("SystemBoltHardware"),
  //   "Joints sucessfully written!");

  return return_type::OK;
}











}  // namespace ros2_control_bolt

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
  ros2_control_bolt::SystemBoltHardware,
  hardware_interface::SystemInterface
)