roscontrol-sot-controller.cpp 38.2 KB
Newer Older
1
#include <dlfcn.h>
Olivier Stasse's avatar
Olivier Stasse committed
2
3
4
5
6
7
#include <fstream>
#include <iomanip>
#include <sstream>

#include "roscontrol-sot-controller.hh"

8
#include <ros/console.h>
Olivier Stasse's avatar
Olivier Stasse committed
9

10
#define ENABLE_RT_LOG
11
#include <dynamic-graph/real-time-logger.h>
12

Olivier Stasse's avatar
Olivier Stasse committed
13
14
15
16
17
18
19
20
21
#if DEBUG
#define ODEBUG(x) std::cout << x << std::endl
#else
#define ODEBUG(x)
#endif
#define ODEBUG3(x) std::cout << x << std::endl

#define DBGFILE "/tmp/rcoh2sot.dat"

22
23
24
25
26
#define RESETDEBUG5()                                                          \
  {                                                                            \
    std::ofstream DebugFile;                                                   \
    DebugFile.open(DBGFILE, std::ofstream::out);                               \
    DebugFile.close();                                                         \
27
  }
28
29
30
31
32
33
34
#define ODEBUG5FULL(x)                                                         \
  {                                                                            \
    std::ofstream DebugFile;                                                   \
    DebugFile.open(DBGFILE, std::ofstream::app);                               \
    DebugFile << __FILE__ << ":" << __FUNCTION__ << "(#" << __LINE__           \
              << "):" << x << std::endl;                                       \
    DebugFile.close();                                                         \
35
  }
36
37
38
39
40
41
#define ODEBUG5(x)                                                             \
  {                                                                            \
    std::ofstream DebugFile;                                                   \
    DebugFile.open(DBGFILE, std::ofstream::app);                               \
    DebugFile << x << std::endl;                                               \
    DebugFile.close();                                                         \
42
  }
Olivier Stasse's avatar
Olivier Stasse committed
43

44
#define RESETDEBUG4()
45
46
#define ODEBUG4FULL(x)
#define ODEBUG4(x)
Olivier Stasse's avatar
Olivier Stasse committed
47

48
class LoggerROSStream : public ::dynamicgraph::LoggerStream {
49
public:
50
  void write(const char *c) { ROS_ERROR("%s", c); }
51
52
};

53
54
55
/// lhi: nickname for local_hardware_interface
/// Depends if we are on the real robot or not.

56
namespace lhi = hardware_interface;
57
58
using namespace lhi;

Olivier Stasse's avatar
Olivier Stasse committed
59
60
using namespace rc_sot_system;

61
62
63
64
65
66
67
68
69
70
71
72
namespace sot_controller {
typedef std::map<std::string, std::string>::iterator it_map_rt_to_sot;
typedef std::map<std::string, std::string>::iterator it_control_mode;

ControlPDMotorControlData::ControlPDMotorControlData() {}

void ControlPDMotorControlData::read_from_xmlrpc_value(
    const std::string &prefix) {
  pid_controller.initParam(prefix);
}

RCSotController::RCSotController()
73
74
75
76
    : // Store 32 DoFs for 5 minutes (1 Khz: 5*60*1000)
      // -> 124 Mo of data.
      type_name_("RCSotController"), simulation_mode_(false),
      accumulated_time_(0.0), jitter_(0.0), verbosity_level_(0) {
77
78
79
80
81
  RESETDEBUG4();
}

void RCSotController::displayClaimedResources(
    ClaimedResources &claimed_resources) {
82
#ifdef CONTROLLER_INTERFACE_KINETIC
83
84
85
86
87
88
89
90
91
92
93
94
95
  ClaimedResources::iterator it_claim;
  ROS_INFO_STREAM("Size of claimed resources: " << claimed_resources.size());
  for (it_claim = claimed_resources.begin();
       it_claim != claimed_resources.end(); ++it_claim) {
    hardware_interface::InterfaceResources &aclaim = *it_claim;
    ROS_INFO_STREAM(
        "Claimed by RCSotController: " << aclaim.hardware_interface);

    for (std::set<std::string>::iterator it_set_res = aclaim.resources.begin();
         it_set_res != aclaim.resources.end(); it_set_res++) {
      ROS_INFO_STREAM(" Resources belonging to the interface:" << *it_set_res);
    }
  }
96
#else
97
98
99
100
101
102
  std::set<std::string>::iterator it_claim;
  ROS_INFO_STREAM("Size of claimed resources: " << claimed_resources.size());
  for (it_claim = claimed_resources.begin();
       it_claim != claimed_resources.end(); ++it_claim) {
    std::string aclaim = *it_claim;
    ROS_INFO_STREAM("Claimed by RCSotController: " << aclaim);
103
  }
104
105
#endif
}
106

107
void RCSotController::initLogs(ros::NodeHandle &robot_nh) {
108
  ROS_INFO_STREAM("Initialize log data structure");
109
110
111
112
113
114
115
116
117
118
119

  int length = 300000;
  if (robot_nh.hasParam("/sot_controller/number_logged_iterations")) {
    robot_nh.getParam("/sot_controller/number_logged_iterations", length);
    int minutes = static_cast<int>(floor(length * dt_ / 60));
    int seconds = static_cast<int>(floor(length * dt_)) - minutes * 60;

    ROS_INFO_STREAM("Number of iterations that will be logged " << length
        << ", i.e. " << minutes << "m" << seconds << "s");
  }

120
121
122
123
124
125
126
  /// Initialize the size of the data to store.
  /// Set temporary profileLog to one
  /// because DataOneIter is just for one iteration.
  profileLog_.length = 1;
  DataOneIter_.init(profileLog_);

  /// Set profile Log to real good value for the stored data.
127
  profileLog_.length = length;
128
129
130
  /// Initialize the data logger for 300s.
  RcSotLog_.init(profileLog_);
}
131

132
133
134
135
136
137
bool RCSotController::initRequest(lhi::RobotHW *robot_hw,
                                  ros::NodeHandle &robot_nh,
                                  ros::NodeHandle &controller_nh,
                                  ClaimedResources &claimed_resources) {
  ROS_WARN("initRequest 1");
  /// Read the parameter server
138
139
  if (!readParams(robot_nh))
    return false;
140
141
142
143
144
145
146
  ROS_WARN("initRequest 2");
  /// Create ros control interfaces to hardware
  /// Recalls: init() is called by initInterfaces()
  if (!initInterfaces(robot_hw, robot_nh, controller_nh, claimed_resources))
    return false;
  ROS_WARN("initRequest 3");
  /// Create all the internal data structures for logging.
147
  initLogs(robot_nh);
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
  ROS_WARN("initRequest 4");
  /// Create SoT
  SotLoaderBasic::Initialization();
  ROS_WARN("initRequest 5");
  /// Fill desired position during the phase where the robot is waiting.
  for (unsigned int idJoint = 0; idJoint < joints_.size(); idJoint++) {
    std::string joint_name = joints_name_[idJoint];
    std::map<std::string, ControlPDMotorControlData>::iterator search_ecpd =
        effort_mode_pd_motors_.find(joint_name);

    if (search_ecpd != effort_mode_pd_motors_.end()) {
      /// If we are in effort mode then the device
      /// should not do any integration.
      sotController_->setNoIntegration();
    }
163
  }
164
165
166
167
168
169
170
  ROS_WARN("initRequest 6");
  return true;
}

bool RCSotController::initInterfaces(lhi::RobotHW *robot_hw, ros::NodeHandle &,
                                     ros::NodeHandle &,
                                     ClaimedResources &claimed_resources) {
171
  using controller_interface::ControllerBase;
172
173
174
175
  std::string lns;
  lns = "hardware_interface";

  // Check if construction finished cleanly
Guilhem Saurel's avatar
Guilhem Saurel committed
176
#ifdef CONTROLLER_INTERFACE_NOETIC
Guilhem Saurel's avatar
Guilhem Saurel committed
177
  if (state_ != ControllerState::CONSTRUCTED) {
Guilhem Saurel's avatar
Guilhem Saurel committed
178
179
180
#else
  if (state_ != CONSTRUCTED) {
#endif
181
182
    ROS_ERROR("Cannot initialize this controller because it "
              "failed to be constructed");
Olivier Stasse's avatar
Olivier Stasse committed
183
184
  }

185
186
187
  // Get a pointer to the joint position control interface
  pos_iface_ = robot_hw->get<PositionJointInterface>();
  if (!pos_iface_) {
188
189
190
191
192
    ROS_WARN("This controller did not find  a hardware interface of type "
             "PositionJointInterface."
             " Make sure this is registered in the %s::RobotHW class "
             "if it is required.",
             lns.c_str());
193
  }
194

195
196
197
  // Get a pointer to the joint velocity control interface
  vel_iface_ = robot_hw->get<VelocityJointInterface>();
  if (!vel_iface_) {
198
199
200
201
202
    ROS_WARN("This controller did not find  a hardware interface of type "
             "VelocityJointInterface."
             " Make sure this is registered in the %s::RobotHW class "
             "if it is required.",
             lns.c_str());
203
  }
Joseph Mirabel's avatar
Joseph Mirabel committed
204

205
206
207
  // Get a pointer to the joint effort control interface
  effort_iface_ = robot_hw->get<EffortJointInterface>();
  if (!effort_iface_) {
208
209
210
211
212
    ROS_WARN("This controller did not find a hardware interface of type "
             "EffortJointInterface."
             " Make sure this is registered in the %s::RobotHW class "
             "if it is required.",
             lns.c_str());
213
  }
Olivier Stasse's avatar
Olivier Stasse committed
214

215
216
217
  // Get a pointer to the force-torque sensor interface
  ft_iface_ = robot_hw->get<ForceTorqueSensorInterface>();
  if (!ft_iface_) {
218
219
220
221
222
    ROS_WARN("This controller did not find a hardware interface of type '%s '. "
             " Make sure this is registered inthe %s::RobotHW class "
             "if it is required.",
             internal ::demangledTypeName<ForceTorqueSensorInterface>().c_str(),
             lns.c_str());
223
224
225
226
227
  }

  // Get a pointer to the IMU sensor interface
  imu_iface_ = robot_hw->get<ImuSensorInterface>();
  if (!imu_iface_) {
228
229
230
231
232
    ROS_WARN("This controller did not find a hardware interface of type '%s'."
             " Make sure this is registered in the %s::RobotHW class "
             "if it is required.",
             internal ::demangledTypeName<ImuSensorInterface>().c_str(),
             lns.c_str());
233
  }
234

235
236
  // Temperature sensor not available in simulation mode
  if (!simulation_mode_) {
237
#ifdef TEMPERATURE_SENSOR_CONTROLLER
238
239
240
241
242
243
244
245
246
247
248
    // Get a pointer to the actuator temperature sensor interface
    act_temp_iface_ = robot_hw->get<ActuatorTemperatureSensorInterface>();
    if (!act_temp_iface_) {
      ROS_WARN(
          "This controller did not find a hardware interface of type '%s'."
          " Make sure this is registered in the %s::RobotHW class if it is"
          " required.",
          internal ::demangledTypeName<ActuatorTemperatureSensorInterface>()
              .c_str(),
          lns.c_str());
    }
249
#endif
250
251
252
  }

  // Return which resources are claimed by this controller
253
254
255
256
257
258
  if (pos_iface_)
    pos_iface_->clearClaims();
  if (vel_iface_)
    vel_iface_->clearClaims();
  if (effort_iface_)
    effort_iface_->clearClaims();
259
260
261
262
263
264
265
266

  if (!init()) {
    ROS_ERROR("Failed to initialize sot-controller");
    std ::cerr << "FAILED LOADING SOT CONTROLLER" << std::endl;
    return false;
  }
  if (verbosity_level_ > 0)
    ROS_INFO_STREAM("Initialization of interfaces for sot-controller Ok !");
Olivier Stasse's avatar
Olivier Stasse committed
267
268

#ifdef CONTROLLER_INTERFACE_KINETIC
269
270
271
272
273
274
275
  hardware_interface::InterfaceResources iface_res;
  iface_res.hardware_interface =
      hardware_interface::internal::demangledTypeName<PositionJointInterface>();
  if (pos_iface_ != 0) {
    iface_res.resources = pos_iface_->getClaims();
    claimed_resources.push_back(iface_res);
  }
Joseph Mirabel's avatar
Joseph Mirabel committed
276

277
278
279
280
281
282
  iface_res.hardware_interface =
      hardware_interface::internal::demangledTypeName<VelocityJointInterface>();
  if (vel_iface_ != 0) {
    iface_res.resources = vel_iface_->getClaims();
    claimed_resources.push_back(iface_res);
  }
Olivier Stasse's avatar
Olivier Stasse committed
283

284
285
286
287
288
289
290
291
  iface_res.hardware_interface =
      hardware_interface::internal::demangledTypeName<EffortJointInterface>();
  if (effort_iface_ != 0) {
    iface_res.resources = effort_iface_->getClaims();
    claimed_resources.push_back(iface_res);
  }

  /// Display claimed ressources
292
293
  if (verbosity_level_ > 0)
    displayClaimedResources(claimed_resources);
294

295
296
  if (pos_iface_ != 0)
    pos_iface_->clearClaims();
Joseph Mirabel's avatar
Joseph Mirabel committed
297

298
299
  if (vel_iface_ != 0)
    vel_iface_->clearClaims();
300

301
302
  if (effort_iface_ != 0)
    effort_iface_->clearClaims();
Olivier Stasse's avatar
Olivier Stasse committed
303
#else
304
305
  claimed_resources = pos_iface_->getClaims();
  /// Display claimed ressources
306
307
308
309
  if (verbosity_level_ > 0)
    displayClaimedResources(claimed_resources);
  if (pos_iface_ != 0)
    pos_iface_->clearClaims();
310
311
312

  claimed_resources = vel_iface_->getClaims();
  /// Display claimed ressources
313
314
315
316
  if (verbosity_level_ > 0)
    displayClaimedResources(claimed_resources);
  if (vel_iface_ != 0)
    vel_iface_->clearClaims();
317
318

  claimed_resources = effort_iface_->getClaims();
319
320
321
322
  if (verbosity_level_ > 0)
    displayClaimedResources(claimed_resources);
  if (effort_iface_ != 0)
    effort_iface_->clearClaims();
323
324
325
326
#endif
  if (verbosity_level_ > 0)
    ROS_INFO_STREAM("Initialization of sot-controller Ok !");
  // success
Guilhem Saurel's avatar
Guilhem Saurel committed
327
#ifdef CONTROLLER_INTERFACE_NOETIC
Guilhem Saurel's avatar
Guilhem Saurel committed
328
  state_ = ControllerState::INITIALIZED;
Guilhem Saurel's avatar
Guilhem Saurel committed
329
330
331
#else
  state_ = INITIALIZED;
#endif
332
333
334
335
  return true;
}

bool RCSotController::init() {
336
337
  if (!initJoints())
    return false;
338
339
340
341
342
343
344
345
  if (!initIMU()) {
    ROS_WARN("could not initialize IMU sensor(s).");
  }
  if (!initForceSensors()) {
    ROS_WARN("could not initialize force sensor(s).");
  }
  if (!initTemperatureSensors()) {
    ROS_WARN("could not initialize temperature sensor(s).");
Olivier Stasse's avatar
Olivier Stasse committed
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

  // Initialize ros node.
  int argc = 1;
  char *argv[1];
  argv[0] = new char[10];
  strcpy(argv[0], "libsot");
  SotLoaderBasic::initializeRosNode(argc, argv);

  return true;
}

void RCSotController::readParamsVerbosityLevel(ros::NodeHandle &robot_nh) {
  if (robot_nh.hasParam("/sot_controller/verbosity_level")) {
    robot_nh.getParam("/sot_controller/verbosity_level", verbosity_level_);
    ROS_INFO_STREAM("Verbosity_level " << verbosity_level_);
  }
  if (robot_nh.hasParam("/sot_controller/log/size")) {
    int llength;
    robot_nh.getParam("/sot_controller/log/size", llength);
    profileLog_.length = (unsigned int)llength;
    ROS_INFO_STREAM("Size of the log " << profileLog_.length);
  }
}

bool RCSotController::readParamsSotLibName(ros::NodeHandle &robot_nh) {
  // Read param to find the library to load
  std::string dynamic_library_name;

  // Read libname
  if (!robot_nh.getParam("/sot_controller/libname", dynamic_library_name)) {
    ROS_ERROR_STREAM("Could not read param /sot_controller/libname");
    if (robot_nh.hasParam("/sot_controller/libname")) {
      ROS_ERROR_STREAM("Param /sot_controller/libname exists !");
    } else {
      ROS_ERROR_STREAM("Param /sot_controller/libname does not exists !");
Olivier Stasse's avatar
Olivier Stasse committed
382
      return false;
383
    }
384
385
386
387
388
389
390
391
392
393
394
395
396
  } else {
    if (verbosity_level_ > 0)
      ROS_INFO_STREAM("Loading library name: " << dynamic_library_name);
  }
  /// SotLoaderBasic related method calls.
  // Initialize the dynamic_library_name for the sotLoader
  setDynamicLibraryName(dynamic_library_name);
  return true;
}

bool RCSotController::readParamsPositionControlData(ros::NodeHandle &) {
  return false;
}
Olivier Stasse's avatar
Olivier Stasse committed
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
bool RCSotController::readParamsEffortControlPDMotorControlData(
    ros::NodeHandle &robot_nh) {
  // Read libname
  if (robot_nh.hasParam("/sot_controller/effort_control_pd_motor_init/gains")) {
    XmlRpc::XmlRpcValue xml_rpc_ecpd_init;
    robot_nh.getParamCached(
        "/sot_controller/effort_control_pd_motor_init/gains",
        xml_rpc_ecpd_init);

    /// Display gain during transition control.
    if (verbosity_level_ > 0)
      ROS_INFO("/sot_controller/effort_control_pd_motor_init/gains: %d %d %d\n",
               xml_rpc_ecpd_init.getType(), XmlRpc::XmlRpcValue::TypeArray,
               XmlRpc::XmlRpcValue::TypeStruct);

    effort_mode_pd_motors_.clear();

    for (size_t i = 0; i < joints_name_.size(); i++) {
      // Check if the joint should be in ROS EFFORT mode
      std::map<std::string, JointSotHandle>::iterator search_joint_sot_handle =
          joints_.find(joints_name_[i]);
      if (search_joint_sot_handle != joints_.end()) {
        JointSotHandle aJointSotHandle = search_joint_sot_handle->second;
        if (aJointSotHandle.ros_control_mode == EFFORT) {
          // Test if PID data is present
          if (xml_rpc_ecpd_init.hasMember(joints_name_[i])) {
            std::string prefix =
                "/sot_controller/effort_control_pd_motor_init/gains/" +
                joints_name_[i];
            effort_mode_pd_motors_[joints_name_[i]].read_from_xmlrpc_value(
                prefix);
          } else
430
431
432
            ROS_ERROR("No PID data for effort controlled joint %s in "
                      "/sot_controller/effort_control_pd_motor_init/gains/",
                      joints_name_[i].c_str());
433
434
435
        }
      }
    }
Olivier Stasse's avatar
Olivier Stasse committed
436
437
438
    return true;
  }

439
440
441
  ROS_WARN("No parameter /sot_controller/effort_controler_pd_motor_init");
  return false;
}
442

443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
bool RCSotController::readParamsVelocityControlPDMotorControlData(
    ros::NodeHandle &robot_nh) {
  // Read libname
  if (robot_nh.hasParam("/sot_controller/velocity_control_pd_motor_init/"
                        "gains")) {
    XmlRpc::XmlRpcValue xml_rpc_ecpd_init;
    robot_nh.getParamCached(
        "/sot_controller/velocity_control_pd_motor_init/gains",
        xml_rpc_ecpd_init);

    /// Display gain during transition control.
    if (verbosity_level_ > 0)
      ROS_INFO(
          "/sot_controller/velocity_control_pd_motor_init/gains: %d %d %d\n",
          xml_rpc_ecpd_init.getType(), XmlRpc::XmlRpcValue::TypeArray,
          XmlRpc::XmlRpcValue::TypeStruct);

    velocity_mode_pd_motors_.clear();

    for (size_t i = 0; i < joints_name_.size(); i++) {
      // Check if the joint should be in ROS VELOCITY mode
      std::map<std::string, JointSotHandle>::iterator search_joint_sot_handle =
          joints_.find(joints_name_[i]);
      if (search_joint_sot_handle != joints_.end()) {
        JointSotHandle aJointSotHandle = search_joint_sot_handle->second;
        if (aJointSotHandle.ros_control_mode == VELOCITY) {
          // Test if PID data is present
          if (xml_rpc_ecpd_init.hasMember(joints_name_[i])) {
            std::string prefix =
                "/sot_controller/velocity_control_pd_motor_init/gains/" +
                joints_name_[i];
            velocity_mode_pd_motors_[joints_name_[i]].read_from_xmlrpc_value(
                prefix);
          } else
477
478
479
            ROS_ERROR("No PID data for velocity controlled joint %s in "
                      "/sot_controller/velocity_control_pd_motor_init/gains/",
                      joints_name_[i].c_str());
480
        }
Olivier Stasse's avatar
Olivier Stasse committed
481
      }
482
    }
Olivier Stasse's avatar
Olivier Stasse committed
483
484
485
    return true;
  }

486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
  ROS_WARN("No parameter /sot_controller/velocity_controler_pd_motor_init");
  return false;
}

bool RCSotController::readParamsFromRCToSotDevice(ros::NodeHandle &robot_nh) {
  // Read libname
  if (robot_nh.hasParam("/sot_controller/map_rc_to_sot_device")) {
    if (robot_nh.getParam("/sot_controller/map_rc_to_sot_device",
                          mapFromRCToSotDevice_)) {
      /// TODO: Check if the mapping is complete wrt to the interface
      /// and the mapping.
      if (verbosity_level_ > 0) {
        ROS_INFO_STREAM("Loading map rc to sot device: ");
        for (it_map_rt_to_sot it = mapFromRCToSotDevice_.begin();
             it != mapFromRCToSotDevice_.end(); ++it)
          ROS_INFO_STREAM(it->first << ", " << it->second);
502
      }
503
    } else {
504
505
      ROS_ERROR_STREAM("Could not read param /sot_controller/"
                       "map_rc_to_sot_device");
506
507
508
      return false;
    }
  } else {
509
510
    ROS_INFO_STREAM("Param /sot_controller/map_rc_to_sot_device "
                    "does not exists !");
511
512
    return false;
  }
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
  return true;
}

bool RCSotController::readParamsJointNames(ros::NodeHandle &robot_nh) {
  /// Check if the /sot_controller/joint_names parameter exists.
  if (robot_nh.hasParam("/sot_controller/joint_names")) {
    /// Read the joint_names list from this parameter
    robot_nh.getParam("/sot_controller/joint_names", joints_name_);
    for (std::vector<std::string>::size_type i = 0; i < joints_name_.size();
         i++) {
      if (verbosity_level_ > 0)
        ROS_INFO_STREAM("joints_name_[" << i << "]=" << joints_name_[i]);

      if (modelURDF_.use_count()) {
        urdf::JointConstSharedPtr aJCSP = modelURDF_->getJoint(joints_name_[i]);
        if (aJCSP.use_count() != 0) {
          if (verbosity_level_ > 0)
            ROS_INFO_STREAM(joints_name_[i] + " found in the robot model");
        } else {
          ROS_ERROR(" %s not found in the robot model",
                    joints_name_[i].c_str());
          return false;
        }
      } else {
        ROS_ERROR("No robot model loaded in /robot_description");
        return false;
Joseph Mirabel's avatar
Joseph Mirabel committed
539
      }
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
    }
  } else
    return false;

  /// Deduce from this the degree of freedom number.
  nbDofs_ = joints_name_.size();
  profileLog_.nbDofs = nbDofs_;

  return true;
}

bool RCSotController::getJointControlMode(std::string &joint_name,
                                          JointSotHandle &aJointSotHandle) {
  std::string scontrol_mode;
  static const std::string seffort("EFFORT"), svelocity("VELOCITY"),
      sposition("POSITION");
  static const std::string ros_control_mode = "ros_control_mode";

  /// Read the list of control_mode
  ros::NodeHandle rnh_ns("/sot_controller/control_mode/" + joint_name);

  ControlMode joint_control_mode;
  if (!rnh_ns.getParam(ros_control_mode, scontrol_mode)) {
    ROS_ERROR("No %s for %s - We found %s", ros_control_mode.c_str(),
              joint_name.c_str(), scontrol_mode.c_str());
Joseph Mirabel's avatar
Joseph Mirabel committed
565
566
    return false;
  }
Olivier Stasse's avatar
Olivier Stasse committed
567

568
569
570
571
572
573
574
575
576
577
578
  if (scontrol_mode == sposition)
    joint_control_mode = POSITION;
  else if (scontrol_mode == svelocity)
    joint_control_mode = VELOCITY;
  else if (scontrol_mode == seffort)
    joint_control_mode = EFFORT;
  else {
    ROS_ERROR("%s for %s not understood. Expected %s, %s or %s. Got %s",
              ros_control_mode.c_str(), joint_name.c_str(), sposition.c_str(),
              svelocity.c_str(), seffort.c_str(), scontrol_mode.c_str());
    return false;
Olivier Stasse's avatar
Olivier Stasse committed
579
580
  }

581
582
  aJointSotHandle.ros_control_mode = joint_control_mode;
  // aJointSotHandle.sot_control_mode = joint_control_mode;
Olivier Stasse's avatar
Olivier Stasse committed
583

584
585
  return true;
}
Olivier Stasse's avatar
Olivier Stasse committed
586

587
588
589
590
591
592
593
594
595
bool RCSotController::readParamsControlMode(ros::NodeHandle &robot_nh) {
  std::map<std::string, std::string> mapControlMode;

  // Read param from control_mode.
  if (robot_nh.hasParam("/sot_controller/control_mode")) {
    /// For each listed joint
    for (unsigned int idJoint = 0; idJoint < joints_name_.size(); idJoint++) {
      std::string joint_name = joints_name_[idJoint];
      JointSotHandle &aJoint = joints_[joint_name];
596
597
      if (!getJointControlMode(joint_name, aJoint))
        return false;
598
599
      ROS_INFO("joint_name[%d]=%s, control_mode=%d", idJoint,
               joint_name.c_str(), aJoint.ros_control_mode);
Joseph Mirabel's avatar
Joseph Mirabel committed
600
    }
601
602
603
604
605
606
  } else {
    ROS_INFO_STREAM("Default control mode : position");
  }
  /// Always return true;
  return true;
}
Joseph Mirabel's avatar
Joseph Mirabel committed
607

608
609
610
611
bool RCSotController::readParamsdt(ros::NodeHandle &robot_nh) {
  /// Reading the jitter is optional but it is a very good idea.
  if (robot_nh.hasParam("/sot_controller/jitter")) {
    robot_nh.getParam("/sot_controller/jitter", jitter_);
612
613
    if (verbosity_level_ > 0)
      ROS_INFO_STREAM("jitter: " << jitter_);
614
  }
615

616
617
618
  /// Read /sot_controller/dt to know what is the control period
  if (robot_nh.hasParam("/sot_controller/dt")) {
    robot_nh.getParam("/sot_controller/dt", dt_);
619
620
    if (verbosity_level_ > 0)
      ROS_INFO_STREAM("dt: " << dt_);
Olivier Stasse's avatar
Olivier Stasse committed
621
622
623
    return true;
  }

624
625
626
  ROS_ERROR("You need to define a control period in param /sot_controller/dt");
  return false;
}
627

628
629
630
631
632
bool RCSotController::readUrdf(ros::NodeHandle &robot_nh) {
  /// Reading the parameter /robot_description which contains the robot
  /// description
  if (!robot_nh.hasParam("/robot_description")) {
    ROS_ERROR("ROS application does not have robot_description");
633
634
    return false;
  }
635
  std::string robot_description_str;
636

637
  robot_nh.getParam("/robot_description", robot_description_str);
638

639
640
641
642
643
  modelURDF_ = urdf::parseURDF(robot_description_str);
  if (verbosity_level_ > 0)
    ROS_INFO("Loaded /robot_description %ld", modelURDF_.use_count());
  return true;
}
Olivier Stasse's avatar
Olivier Stasse committed
644

645
646
647
648
649
bool RCSotController::readParams(ros::NodeHandle &robot_nh) {
  /// Read the level of verbosity for the controller
  /// (0: quiet, 1: info, 2: debug).
  /// Default to quiet
  readParamsVerbosityLevel(robot_nh);
Olivier Stasse's avatar
Olivier Stasse committed
650

651
  /// Reads the SoT dynamic library name.
652
653
  if (!readParamsSotLibName(robot_nh))
    return false;
Olivier Stasse's avatar
Olivier Stasse committed
654

655
656
657
658
659
  /// Read /sot_controller/simulation_mode to know
  /// if we are in simulation mode
  // Defines if we are in simulation node.
  if (robot_nh.hasParam("/sot_controller/simulation_mode"))
    simulation_mode_ = true;
660

661
662
  /// Read URDF file.
  readUrdf(robot_nh);
Olivier Stasse's avatar
Olivier Stasse committed
663

664
665
  /// Calls readParamsJointNames
  // Reads the list of joints to be controlled.
666
667
  if (!readParamsJointNames(robot_nh))
    return false;
668
669
670

  /// Calls readParamsControlMode.
  // Defines if the control mode is position or effort
671
672
  if (!readParamsControlMode(robot_nh))
    return false;
673
674
675
676
677
678

  /// Calls readParamsFromRCToSotDevice
  // Mapping from ros-controll to sot device
  readParamsFromRCToSotDevice(robot_nh);

  /// Get control period
679
680
  if (!readParamsdt(robot_nh))
    return false;
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699

  readParamsEffortControlPDMotorControlData(robot_nh);
  readParamsVelocityControlPDMotorControlData(robot_nh);
  readParamsPositionControlData(robot_nh);
  return true;
}

bool RCSotController::initJoints() {
  // Init Joint Names.
  //    joints_.resize(joints_name_.size());

  for (unsigned int i = 0; i < nbDofs_; i++) {
    bool notok = true;

    while (notok) {
      std::string &joint_name = joints_name_[i];
      try {
        JointSotHandle &aJointSotHandle = joints_[joint_name];
        switch (aJointSotHandle.ros_control_mode) {
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
        case POSITION:
          aJointSotHandle.joint = pos_iface_->getHandle(joint_name);
          if (verbosity_level_ > 0)
            ROS_INFO_STREAM("Found joint " << joint_name << " in position " << i
                                           << " "
                                           << aJointSotHandle.joint.getName());
          break;
        case VELOCITY:
          aJointSotHandle.joint = vel_iface_->getHandle(joint_name);
          if (verbosity_level_ > 0)
            ROS_INFO_STREAM("Found joint " << joint_name << " in velocity " << i
                                           << " "
                                           << aJointSotHandle.joint.getName());
          break;
        case EFFORT:
          aJointSotHandle.joint = effort_iface_->getHandle(joint_name);
          if (verbosity_level_ > 0)
            ROS_INFO_STREAM("Found joint " << joint_name << " in effort " << i
                                           << " "
                                           << aJointSotHandle.joint.getName());
720
721
722
723
724
725
726
727
728
        }

        // throws on failure
        notok = false;
        aJointSotHandle.desired_init_pose = aJointSotHandle.joint.getPosition();

      } catch (...) {
        ROS_ERROR_STREAM("Could not find joint " << joint_name);
        return false;
729
      }
Olivier Stasse's avatar
Olivier Stasse committed
730
731
    }
  }
732
733
734
735
736

  return true;
}

bool RCSotController::initIMU() {
737
738
  if (!imu_iface_)
    return false;
739
740
741
742
743
744
745
746
747
748

  // get all imu sensor names
  const std ::vector<std ::string> &imu_iface_names = imu_iface_->getNames();
  if (verbosity_level_ > 0) {
    for (unsigned i = 0; i < imu_iface_names.size(); i++)
      ROS_INFO("Got sensor %s", imu_iface_names[i].c_str());
  }
  for (unsigned i = 0; i < imu_iface_names.size(); i++) {
    // sensor handle on imu
    imu_sensor_.push_back(imu_iface_->getHandle(imu_iface_names[i]));
Olivier Stasse's avatar
Olivier Stasse committed
749
750
  }

751
752
  return true;
}
753

754
bool RCSotController::initForceSensors() {
755
756
  if (!ft_iface_)
    return false;
757
758
759
760
761
762

  // get force torque sensors names package.
  const std::vector<std::string> &ft_iface_names = ft_iface_->getNames();
  if (verbosity_level_ > 0) {
    for (unsigned i = 0; i < ft_iface_names.size(); i++)
      ROS_INFO("Got sensor %s", ft_iface_names[i].c_str());
763
  }
764
765
766
  for (unsigned i = 0; i < ft_iface_names.size(); i++) {
    // sensor handle on torque forces
    ft_sensors_.push_back(ft_iface_->getHandle(ft_iface_names[i]));
Olivier Stasse's avatar
Olivier Stasse committed
767
  }
768
769
770
  profileLog_.nbForceSensors = ft_iface_names.size();
  return true;
}
Olivier Stasse's avatar
Olivier Stasse committed
771

772
773
bool RCSotController::initTemperatureSensors() {
  if (!simulation_mode_) {
774
#ifdef TEMPERATURE_SENSOR_CONTROLLER
775
776
    if (!act_temp_iface_)
      return false;
777
778
779
780
781
782
783
784

    // get temperature sensors names
    const std::vector<std::string> &act_temp_iface_names =
        act_temp_iface_->getNames();

    if (verbosity_level_ > 0) {
      ROS_INFO("Actuator temperature sensors: %ld",
               act_temp_iface_names.size());
785

786
787
788
789
790
791
792
793
794
      for (unsigned i = 0; i < act_temp_iface_names.size(); i++)
        ROS_INFO("Got sensor %s", act_temp_iface_names[i].c_str());
    }

    for (unsigned i = 0; i < act_temp_iface_names.size(); i++) {
      // sensor handle on actuator temperature
      act_temp_sensors_.push_back(
          act_temp_iface_->getHandle(act_temp_iface_names[i]));
    }
795
#endif
Olivier Stasse's avatar
Olivier Stasse committed
796
797
  }

798
799
  return true;
}
Olivier Stasse's avatar
Olivier Stasse committed
800

801
802
803
804
805
806
807
808
809
810
811
void RCSotController::fillSensorsIn(std::string &title,
                                    std::vector<double> &data) {
  /// Tries to find the mapping from the local validation
  /// to the SoT device.
  it_map_rt_to_sot it_mapRC2Sot = mapFromRCToSotDevice_.find(title);
  /// If the mapping is found
  if (it_mapRC2Sot != mapFromRCToSotDevice_.end()) {
    /// Expose the data to the SoT device.
    std::string lmapRC2Sot = it_mapRC2Sot->second;
    sensorsIn_[lmapRC2Sot].setName(lmapRC2Sot);
    sensorsIn_[lmapRC2Sot].setValues(data);
Olivier Stasse's avatar
Olivier Stasse committed
812
  }
813
}
Olivier Stasse's avatar
Olivier Stasse committed
814

815
816
817
818
819
820
821
822
823
824
825
826
void RCSotController::fillJoints() {
  /// Fill positions, velocities and torques.
  for (unsigned int idJoint = 0; idJoint < joints_name_.size(); idJoint++) {
    it_joint_sot_h anItJoint = joints_.find(joints_name_[idJoint]);
    if (anItJoint != joints_.end()) {
      JointSotHandle &aJoint = anItJoint->second;
      DataOneIter_.motor_angle[idJoint] = aJoint.joint.getPosition();

#ifdef TEMPERATURE_SENSOR_CONTROLLER
      DataOneIter_.joint_angle[idJoint] = aJoint.joint.getAbsolutePosition();
#endif
      DataOneIter_.velocities[idJoint] = aJoint.joint.getVelocity();
Olivier Stasse's avatar
Olivier Stasse committed
827

828
#ifdef TEMPERATURE_SENSOR_CONTROLLER
829
      DataOneIter_.torques[idJoint] = aJoint.joint.getTorqueSensor();
830
#endif
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
      DataOneIter_.motor_currents[idJoint] = aJoint.joint.getEffort();
    }
  }

  /// Update SoT internal values
  std::string ltitle("motor-angles");
  fillSensorsIn(ltitle, DataOneIter_.motor_angle);
  ltitle = "joint-angles";
  fillSensorsIn(ltitle, DataOneIter_.joint_angle);
  ltitle = "velocities";
  fillSensorsIn(ltitle, DataOneIter_.velocities);
  ltitle = "torques";
  fillSensorsIn(ltitle, DataOneIter_.torques);
  ltitle = "currents";
  fillSensorsIn(ltitle, DataOneIter_.motor_currents);
}

void RCSotController::setSensorsImu(std::string &name, int IMUnb,
                                    std::vector<double> &data) {
  std::ostringstream labelOss;
  labelOss << name << IMUnb;
  std::string label_s = labelOss.str();
  fillSensorsIn(label_s, data);
}

void RCSotController::fillImu() {
  for (unsigned int idIMU = 0; idIMU < imu_sensor_.size(); idIMU++) {
    /// Fill orientations, gyrometer and acceleration from IMU.
    if (imu_sensor_[idIMU].getOrientation()) {
      for (unsigned int idquat = 0; idquat < 4; idquat++) {
        DataOneIter_.orientation[idquat] =
            imu_sensor_[idIMU].getOrientation()[idquat];
863
      }
864
865
866
867
868
    }
    if (imu_sensor_[idIMU].getAngularVelocity()) {
      for (unsigned int idgyrometer = 0; idgyrometer < 3; idgyrometer++) {
        DataOneIter_.gyrometer[idgyrometer] =
            imu_sensor_[idIMU].getAngularVelocity()[idgyrometer];
869
      }
870
871
872
873
874
875
876
877
878
879
880
881
882
    }
    if (imu_sensor_[idIMU].getLinearAcceleration()) {
      for (unsigned int idlinacc = 0; idlinacc < 3; idlinacc++) {
        DataOneIter_.accelerometer[idlinacc] =
            imu_sensor_[idIMU].getLinearAcceleration()[idlinacc];
      }
    }

    std::string orientation_s("orientation_");
    setSensorsImu(orientation_s, idIMU, DataOneIter_.orientation);

    std::string gyrometer_s("gyrometer_");
    setSensorsImu(gyrometer_s, idIMU, DataOneIter_.gyrometer);
883

884
885
    std::string accelerometer_s("accelerometer_");
    setSensorsImu(accelerometer_s, idIMU, DataOneIter_.accelerometer);
886
  }
887
}
Olivier Stasse's avatar
Olivier Stasse committed
888

889
890
891
892
893
894
895
896
void RCSotController::fillForceSensors() {
  for (unsigned int idFS = 0; idFS < ft_sensors_.size(); idFS++) {
    for (unsigned int idForce = 0; idForce < 3; idForce++)
      DataOneIter_.force_sensors[idFS * 6 + idForce] =
          ft_sensors_[idFS].getForce()[idForce];
    for (unsigned int idTorque = 0; idTorque < 3; idTorque++)
      DataOneIter_.force_sensors[idFS * 6 + 3 + idTorque] =
          ft_sensors_[idFS].getTorque()[idTorque];
Olivier Stasse's avatar
Olivier Stasse committed
897
  }
Joseph Mirabel's avatar
Joseph Mirabel committed
898

899
900
901
902
903
904
905
906
907
908
909
910
911
912
  std::string alabel("forces");
  fillSensorsIn(alabel, DataOneIter_.force_sensors);
}

void RCSotController::fillTempSensors() {
  if (!simulation_mode_) {
#ifdef TEMPERATURE_SENSOR_CONTROLLER
    for (unsigned int idFS = 0; idFS < act_temp_sensors_.size(); idFS++) {
      DataOneIter_.temperatures[idFS] = act_temp_sensors_[idFS].getValue();
    }
#endif
  } else {
    for (unsigned int idFS = 0; idFS < nbDofs_; idFS++)
      DataOneIter_.temperatures[idFS] = 0.0;
Olivier Stasse's avatar
Olivier Stasse committed
913
914
  }

915
916
917
  std::string alabel("act-temp");
  fillSensorsIn(alabel, DataOneIter_.temperatures);
}
Olivier Stasse's avatar
Olivier Stasse committed
918

919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
void RCSotController::fillSensors() {
  fillJoints();
  fillImu();
  fillForceSensors();
  fillTempSensors();
}

void RCSotController::readControl(
    std::map<std::string, dgs::ControlValues> &controlValues) {
  ODEBUG4("joints_.size() = " << joints_.size());
  std::string cmdTitle = "control";

  it_map_rt_to_sot it_mapRC2Sot = mapFromRCToSotDevice_.find(cmdTitle);
  if (it_mapRC2Sot != mapFromRCToSotDevice_.end()) {
    std::string &lmapRC2Sot = it_mapRC2Sot->second;
    command_ = controlValues[lmapRC2Sot].getValues();
    ODEBUG4("angleControl_.size() = " << command_.size());
    for (unsigned int i = 0; i < command_.size(); ++i) {
      joints_[joints_name_[i]].joint.setCommand(command_[i]);
      DataOneIter_.controls[i] = command_[i];
    }

  } else
    ROS_INFO_STREAM("no control.");
}

void RCSotController::one_iteration() {
  // Chrono start
  RcSotLog_.start_it();

  /// Update the sensors.
  fillSensors();

  /// Generate a control law.
  try {
    sotController_->nominalSetSensors(sensorsIn_);
955
956
957
958
959
960
961
962
963
  } catch (std::exception &e) {
    std::cerr << "Failure happened during one_iteration(): "
              << "when calling nominalSetSensors " << std::endl ;
    std::cerr << __FILE__ << " " << __LINE__ << std::endl
              << e.what() << std::endl;

    throw e;
  }
  try {
964
965
    sotController_->getControl(controlValues_);
  } catch (std::exception &e) {
966
967
968
969
    std::cerr << "Failure happened during one_iteration(): "
              << "when calling getControl " << std::endl;
    std::cerr << __FILE__ << " " << __LINE__ << std::endl
              << e.what() << std::endl;;
970
    throw e;
Olivier Stasse's avatar
Olivier Stasse committed
971
972
  }

973

974
975
976
977
  /// Read the control values
  readControl(controlValues_);

  // Chrono stop.
978
979
980
981
982
  double it_duration = RcSotLog_.stop_it();
  if (it_duration > dt_) {
    ROS_WARN_THROTTLE(1, "Iteration duration (%d) bigger than max period (%d)",
        it_duration, dt_);
  }
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009

  /// Store everything in Log.
  RcSotLog_.record(DataOneIter_);
}

void RCSotController::localStandbyEffortControlMode(
    const ros::Duration &period) {
  // ROS_INFO("Compute command for effort mode: %d %d",joints_.size(),
  // effort_mode_pd_motors_.size());
  for (unsigned int idJoint = 0; idJoint < joints_.size(); idJoint++) {
    std::string joint_name = joints_name_[idJoint];
    std::map<std::string, ControlPDMotorControlData>::iterator search_ecpd =
        effort_mode_pd_motors_.find(joint_name);

    if (search_ecpd != effort_mode_pd_motors_.end()) {
      ControlPDMotorControlData &ecpdcdata = search_ecpd->second;
      JointSotHandle &aJointSotHandle = joints_[joint_name];
      lhi::JointHandle &aJoint = aJointSotHandle.joint;

      double vel_err = 0 - aJoint.getVelocity();
      double err = aJointSotHandle.desired_init_pose - aJoint.getPosition();

      double local_command =
          ecpdcdata.pid_controller.computeCommand(err, vel_err, period);
      // Apply command
      aJoint.setCommand(local_command);
    }
1010
  }
1011
}
Joseph Mirabel's avatar
Joseph Mirabel committed
1012

1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
void RCSotController::localStandbyVelocityControlMode(
    const ros::Duration &period) {
  static bool first_time = true;

  /// Iterate over all the joints
  for (unsigned int idJoint = 0; idJoint < joints_.size(); idJoint++) {
    /// Find the joint
    std::string joint_name = joints_name_[idJoint];
    std::map<std::string, ControlPDMotorControlData>::iterator search_ecpd =
        velocity_mode_pd_motors_.find(joint_name);

    if (search_ecpd != velocity_mode_pd_motors_.end()) {
      ControlPDMotorControlData &ecpdcdata = search_ecpd->second;
      JointSotHandle &aJointSotHandle = joints_[joint_name];
      lhi::JointHandle &aJoint = aJointSotHandle.joint;

      double vel_err = 0 - aJoint.getVelocity();
      double err = aJointSotHandle.desired_init_pose - aJoint.getPosition();

      double local_command =
          ecpdcdata.pid_controller.computeCommand(err, vel_err, period);

      aJoint.setCommand(local_command);

      assert(aJoint.getName() == joint_name);
      if (first_time)
        if (verbosity_level_ > 1) {
1040
1041
          ROS_INFO("Velocity control mode: control joint %s (id %d) to %f\n",
		   joint_name.c_str(), idJoint, aJoint.getPosition());
1042
1043
        }
    }
Joseph Mirabel's avatar
Joseph Mirabel committed
1044
  }
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
  first_time = false;
}

void RCSotController::localStandbyPositionControlMode() {
  static bool first_time = true;

  /// Iterate over all the joints
  for (unsigned int idJoint = 0; idJoint < joints_.size(); idJoint++) {
    /// Find the joint
    std::string joint_name = joints_name_[idJoint];

    // If it is position mode control.
    if (joints_[joint_name].ros_control_mode == POSITION) {
      JointSotHandle &aJointSotHandle = joints_[joint_name];
      lhi::JointHandle &aJoint = aJointSotHandle.joint;

      aJoint.setCommand(aJointSotHandle.desired_init_pose);

      assert(aJoint.getName() == joint_name);
      if (first_time)
        if (verbosity_level_ > 1) {
1066
1067
          ROS_INFO("Position control mode: control joint %s (id %d) to %f\n",
		   joint_name.c_str(), idJoint, aJoint.getPosition());
1068
1069
        }
    }
1070
  }
1071
1072
  first_time = false;
}
1073

1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
void RCSotController::update(const ros::Time &, const ros::Duration &period) {
  // Do not send any control if the dynamic graph is not started
  if (!isDynamicGraphStopped()) {
    try {
      double periodInSec = period.toSec();
      if (periodInSec + accumulated_time_ > dt_ - jitter_) {
        one_iteration();
        accumulated_time_ = 0.0;
      } else
        accumulated_time_ += periodInSec;
    } catch (std::exception const &exc) {
Joseph Mirabel's avatar
Joseph Mirabel committed
1085
1086
1087
1088
      ROS_ERROR_STREAM("Failure happened during one_iteration evaluation: "
                << exc.what() << "\nUse gdb to investiguate the problem\n"
                << __FILE__ << ":" << __LINE__);
      throw;
1089
    } catch (...) {
Joseph Mirabel's avatar
Joseph Mirabel committed
1090
1091
1092
1093
      ROS_ERROR_STREAM("Failure happened during one_iteration evaluation: "
                "unknown exception\nUse gdb to investiguate the problem\n"
                << __FILE__ << ":" << __LINE__);
      throw;
1094
1095
1096
    }
  } else {
    /// Update the sensors.
Olivier Stasse's avatar
Olivier Stasse committed
1097
    fillSensors();
1098
1099
    try {
      sotController_->setupSetSensors(sensorsIn_);
1100
    } catch (std::exception &e) {
Joseph Mirabel's avatar
Joseph Mirabel committed
1101
1102
      ROS_ERROR_STREAM("RCSotController::update: " << e.what());
      throw;
1103
    }
1104
1105
1106
1107
1108
1109
    // But in effort mode it means that we are sending 0
    // Therefore implements a default PD controller on the system.
    // Applying both to handle mixed system.
    localStandbyEffortControlMode(period);
    localStandbyVelocityControlMode(period);
    localStandbyPositionControlMode();
1110
  }
1111
1112
1113
1114
1115
1116
}

void RCSotController::starting(const ros::Time &) {
  using namespace ::dynamicgraph;
  RealTimeLogger::instance().addOutputStream(
      LoggerStreamPtr_t(new LoggerROSStream()));
Olivier Stasse's avatar
Olivier Stasse committed
1117

1118
  fillSensors();
Olivier Stasse's avatar
Olivier Stasse committed
1119
}
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131

void RCSotController::stopping(const ros::Time &) {
  std::string afilename("/tmp/sot.log");
  RcSotLog_.save(afilename);

  SotLoaderBasic::CleanUp();

  using namespace ::dynamicgraph;
  RealTimeLogger::destroy();
}

PLUGINLIB_EXPORT_CLASS(sot_controller::RCSotController, lci::ControllerBase)
1132
} // namespace sot_controller