system_bolt.cpp 20.7 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
{
55
56
  //Define the ODRI robot from URDF values

Paul Rouanet's avatar
Paul Rouanet committed
57
58
  // Get the ethernet interface to discuss with the ODRI master board
  eth_interface_ = info_.hardware_parameters.at("eth_interface");
59
 
Paul Rouanet's avatar
Paul Rouanet committed
60
  // Define board (ODRI)
61
  main_board_ptr_ = std::make_shared<MasterBoardInterface>(eth_interface_);
Paul Rouanet's avatar
Paul Rouanet committed
62
63
64

  // Define joints (ODRI)
  for (const hardware_interface::ComponentInfo & joint : info.joints) {
65
66
67
68
69
70
71
72
73
74
    // 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
75
76
    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)
77
78
79
80
81
82
    
    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
83
84
  }

85
  joints_ = std::make_shared<JointModules>(main_board_ptr_,
Paul Rouanet's avatar
Paul Rouanet committed
86
                                               motor_numbers_,
Paul Rouanet's avatar
Paul Rouanet committed
87
88
89
90
91
92
93
94
                                               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
95

96
97
98
99
  // Get position offset of each joint
    for (const hardware_interface::ComponentInfo & joint : info.joints) {
      position_offsets_[joint_name_to_motor_nb_[joint.name]] = stod(joint.parameters.at("position_offset"));   //Modif d'après lecture des capteurs (demo bolt)
    }
100

Paul Rouanet's avatar
Paul Rouanet committed
101
  // Define the IMU (ODRI).
102
103
104
105
106
107
108
109
110
111
  for (const hardware_interface::ComponentInfo & sensor : info.sensors) {
    std::istringstream iss_rotate (sensor.parameters.at("rotate_vector"));
    std::istringstream iss_orientation (sensor.parameters.at("orientation_vector"));
    for (int n=0; n<3; n++){
      iss_rotate >> rotate_vector_[n];
    }
    for (int n=0; n<4; n++){
      iss_orientation >> orientation_vector_[n];
    }
  }
Paul Rouanet's avatar
Paul Rouanet committed
112
  auto imu = std::make_shared<IMU>(
113
      main_board_ptr_, rotate_vector_, orientation_vector_);
114
115


Paul Rouanet's avatar
Paul Rouanet committed
116
  // Define the robot (ODRI).
117
  robot_ = std::make_shared<Robot>(main_board_ptr_, joints_, imu);
Paul Rouanet's avatar
Paul Rouanet committed
118
119
120
121
122
123

return return_type::OK;
}



Paul Rouanet's avatar
Paul Rouanet committed
124
125
126
127
128
129
130
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
131

Paul Rouanet's avatar
Paul Rouanet committed
132
133
134
135
  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"]);

136
137
138
139
140
141
142
143
144
  //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
145
146
  // For each joint.
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
147
148
149

    // Map joint with motor number
    // (uses at instead of [] because of joint constantness)
Paul Rouanet's avatar
Paul Rouanet committed
150
    joint_name_to_motor_nb_[joint.name] = stoi(joint.parameters.at("motor_number"));
Paul Rouanet's avatar
Paul Rouanet committed
151
152
153
154
    
    // 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
155
156
157
158
159
160
161
162
163
164
165
166
167
    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;
168

169
     
Paul Rouanet's avatar
Paul Rouanet committed
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
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

    // 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
243
244
  

Paul Rouanet's avatar
Paul Rouanet committed
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
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
  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;
}

417
//Calibration function
418
return_type SystemBoltHardware::calibration(){
Paul Rouanet's avatar
Paul Rouanet committed
419

420
421
422
423
    double Kp = stod(info_.hardware_parameters.at("calib_kp"));
    double Kd = stod(info_.hardware_parameters.at("calib_kd"));
    double T = stod(info_.hardware_parameters.at("calib_T"));
    double dt = stod(info_.hardware_parameters.at("calib_dt"));
424
425
426
427
428
429
430
    std::vector<CalibrationMethod> directions = {
        AUTO, AUTO, AUTO, AUTO, AUTO, AUTO}; 
    auto calib_ctrl = std::make_shared<JointCalibrator>(
        joints_, directions, position_offsets_, Kp, Kd, T, dt);

    robot_->RunCalibration(calib_ctrl);

431
432
    return return_type::OK;
  }
433
434


435
436
437
438
439
return_type SystemBoltHardware::start()
{
  robot_->Start();

  
440
441
442
443
444
445
446
  // 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
447

448
  // Calibration
449
  calibration();
450
451
452
453

  // Sensor reading
  read();

454
  status_ = hardware_interface::status::STARTED;
Paul Rouanet's avatar
Paul Rouanet committed
455
456
457
458
459
460
461

  return return_type::OK;
}


return_type SystemBoltHardware::stop()
{
462
463
  // Stop the MasterBoard
  main_board_ptr_->Stop();
Paul Rouanet's avatar
Paul Rouanet committed
464
465
466
467
468
469
470

  return return_type::OK;
}


hardware_interface::return_type SystemBoltHardware::read()
{
Paul Rouanet's avatar
Paul Rouanet committed
471
  // Data acquisition (with ODRI)
Paul Rouanet's avatar
Paul Rouanet committed
472
  robot_->ParseSensorData();
Paul Rouanet's avatar
Paul Rouanet committed
473

Paul Rouanet's avatar
Paul Rouanet committed
474
475
476
  auto sensor_positions = robot_->joints->GetPositions();
  auto sensor_velocities = robot_->joints->GetVelocities();
  auto measured_torques = robot_->joints->GetMeasuredTorques();
477
   
Paul Rouanet's avatar
Paul Rouanet committed
478
479
480
481
482
  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
483

Paul Rouanet's avatar
Paul Rouanet committed
484

Paul Rouanet's avatar
Paul Rouanet committed
485
  // Assignment of sensor data to ros2_control variables (URDF)
Paul Rouanet's avatar
Paul Rouanet committed
486
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
487
488
489
    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]];
490
491
    hw_states_[joint.name].Kp = stod(joint.parameters.at("kp"));
    hw_states_[joint.name].Kd = stod(joint.parameters.at("kd"));
Paul Rouanet's avatar
Paul Rouanet committed
492
  }
Paul Rouanet's avatar
Paul Rouanet committed
493
494
  
  // Assignment of IMU data (URDF)
495
  // Modif with for loop possible to optimize the code
Paul Rouanet's avatar
Paul Rouanet committed
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
  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];
  
Paul Rouanet's avatar
Paul Rouanet committed
517
518
519
520
521
522
523
  return return_type::OK;
}


hardware_interface::return_type
SystemBoltHardware::write()
{
524
525
526
527
  
  Eigen::Vector6d positions;
  Eigen::Vector6d velocities;
  Eigen::Vector6d torques;
Paul Rouanet's avatar
Paul Rouanet committed
528
529
  Eigen::Vector6d gain_KP;
  Eigen::Vector6d gain_KD;
530

Paul Rouanet's avatar
Paul Rouanet committed
531
532
533
534
535
536
537
538
539
540
541
542
  for (const hardware_interface::ComponentInfo & joint : info_.joints) {
    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;
  }
  robot_->joints->SetDesiredPositions(positions);
  robot_->joints->SetDesiredVelocities(velocities);
  robot_->joints->SetTorques(torques);
  robot_->joints->SetPositionGains(gain_KP);
  robot_->joints->SetVelocityGains(gain_KD);
543

Paul Rouanet's avatar
Paul Rouanet committed
544
/*
545
546
  std::chrono::time_point<std::chrono::system_clock> last = std::chrono::system_clock::now();

Paul Rouanet's avatar
Paul Rouanet committed
547
  while (!robot_->IsTimeout()) {
548
549
550
551
    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
552
      if (robot_->IsReady()) {
553
554
        
        // Control law        
Paul Rouanet's avatar
Paul Rouanet committed
555
556
        positions = ...;
        torques =  ...;
557
558
        
        for (const hardware_interface::ComponentInfo & joint : info_.joints) {
Paul Rouanet's avatar
Paul Rouanet committed
559
560
561
562
563
          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
564
        }
565

Paul Rouanet's avatar
Paul Rouanet committed
566
567
568
569
570
        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
571
          
572
573
      }
    }
Paul Rouanet's avatar
Paul Rouanet committed
574
575
576
577
578
    else
        {
            std::this_thread::yield();
        }

Paul Rouanet's avatar
Paul Rouanet committed
579
    robot_->SendCommand();
580
581
582
  }


Paul Rouanet's avatar
Paul Rouanet committed
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
  // 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"),
Paul Rouanet's avatar
Paul Rouanet committed
600
  //   "Joints sucessfully written!");*/
Paul Rouanet's avatar
Paul Rouanet committed
601
602
603
604
605
606
607
608
609
610
611
612
613
614

  return return_type::OK;
}



}  // namespace ros2_control_bolt

#include "pluginlib/class_list_macros.hpp"

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