diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 92fd52d..f73e12f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -2,7 +2,7 @@ ci: autoupdate_branch: 'devel' repos: - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v20.1.8 + rev: v21.1.2 hooks: - id: clang-format args: [--style=Google] @@ -24,8 +24,8 @@ repos: - id: fix-byte-order-marker - id: mixed-line-ending - id: trailing-whitespace -- repo: https://github.com/psf/black - rev: 25.1.0 +- repo: https://github.com/psf/black-pre-commit-mirror + rev: 25.9.0 hooks: - id: black - repo: https://github.com/PyCQA/flake8 diff --git a/src/log.cpp b/src/log.cpp index e2b1a0f..deb81b9 100644 --- a/src/log.cpp +++ b/src/log.cpp @@ -16,7 +16,7 @@ using namespace rc_sot_system; DataToLog::DataToLog() {} -void DataToLog::init(ProfileLog &aProfileLog) { +void DataToLog::init(ProfileLog& aProfileLog) { profileLog_ = aProfileLog; motor_angle.resize(aProfileLog.nbDofs * aProfileLog.length); joint_angle.resize(aProfileLog.nbDofs * aProfileLog.length); @@ -53,7 +53,7 @@ void DataToLog::init(ProfileLog &aProfileLog) { Log::Log() : lref_(0), lrefts_(0) {} -void Log::init(ProfileLog &aProfileLog) { +void Log::init(ProfileLog& aProfileLog) { profileLog_ = aProfileLog; lref_ = 0; lrefts_ = 0; @@ -64,7 +64,7 @@ void Log::init(ProfileLog &aProfileLog) { timeorigin_ = (double)current.tv_sec + 0.000001 * ((double)current.tv_usec); } -void Log::record(DataToLog &aDataToLog) { +void Log::record(DataToLog& aDataToLog) { if ((aDataToLog.motor_angle.size() != profileLog_.nbDofs) || (aDataToLog.velocities.size() != profileLog_.nbDofs)) return; @@ -148,7 +148,7 @@ double Log::stop_it() { return time_stop_it_ - time_start_it_; } -void Log::save(std::string &fileName) { +void Log::save(std::string& fileName) { assert(lref_ == lrefts_ * profileLog_.nbDofs); std::string suffix("-mastate.log"); @@ -184,22 +184,22 @@ void Log::save(std::string &fileName) { saveVector(fileName, suffix, StoredData_.duration, 1); } -inline void writeHeaderToBinaryBuffer(ofstream &of, const std::size_t &nVector, - const std::size_t &vectorSize) { - of.write((const char *)(&nVector), sizeof(std::size_t)); - of.write((const char *)(&vectorSize), sizeof(std::size_t)); +inline void writeHeaderToBinaryBuffer(ofstream& of, const std::size_t& nVector, + const std::size_t& vectorSize) { + of.write((const char*)(&nVector), sizeof(std::size_t)); + of.write((const char*)(&vectorSize), sizeof(std::size_t)); } -inline void writeToBinaryFile(ofstream &of, const double &t, const double &dt, - const std::vector &data, - const std::size_t &idx, const std::size_t &size) { - of.write((const char *)&t, sizeof(double)); - of.write((const char *)&dt, sizeof(double)); - of.write((const char *)(&data[idx]), size * (sizeof(double))); +inline void writeToBinaryFile(ofstream& of, const double& t, const double& dt, + const std::vector& data, + const std::size_t& idx, const std::size_t& size) { + of.write((const char*)&t, sizeof(double)); + of.write((const char*)&dt, sizeof(double)); + of.write((const char*)(&data[idx]), size * (sizeof(double))); } -void Log::saveVector(std::string &fileName, std::string &suffix, - const std::vector &avector, std::size_t size) { +void Log::saveVector(std::string& fileName, std::string& suffix, + const std::vector& avector, std::size_t size) { ostringstream oss; oss << fileName; oss << suffix.c_str(); diff --git a/src/log.hh b/src/log.hh index a840a08..8ac4e12 100644 --- a/src/log.hh +++ b/src/log.hh @@ -50,7 +50,7 @@ struct DataToLog { ProfileLog profileLog_; DataToLog(); - void init(ProfileLog &aProfileLog); + void init(ProfileLog& aProfileLog); std::size_t nbDofs() { return profileLog_.nbDofs; } std::size_t nbForceSensors() { return profileLog_.nbForceSensors; } std::size_t length() { return profileLog_.length; } @@ -78,16 +78,16 @@ class Log { // \param size number of contiguous values of avector that forms one line. // \note avector is a circular buffer. Data will be written from // start to N, and then from 0 to start. - void saveVector(std::string &filename, std::string &suffix, - const std::vector &avector, std::size_t size); + void saveVector(std::string& filename, std::string& suffix, + const std::vector& avector, std::size_t size); public: Log(); - void init(ProfileLog &aProfileLog); - void record(DataToLog &aDataToLog); + void init(ProfileLog& aProfileLog); + void record(DataToLog& aDataToLog); - void save(std::string &fileName); + void save(std::string& fileName); void start_it(); /// \return the elapsed time since the previous \ref start_it double stop_it(); diff --git a/src/roscontrol-sot-controller.cpp b/src/roscontrol-sot-controller.cpp index 73d79fa..fc386f7 100644 --- a/src/roscontrol-sot-controller.cpp +++ b/src/roscontrol-sot-controller.cpp @@ -47,7 +47,7 @@ class LoggerROSStream : public ::dynamicgraph::LoggerStream { public: - void write(const char *c) { ROS_ERROR("%s", c); } + void write(const char* c) { ROS_ERROR("%s", c); } }; /// lhi: nickname for local_hardware_interface @@ -65,7 +65,7 @@ typedef dynamicgraph::size_type size_type; ControlPDMotorControlData::ControlPDMotorControlData() {} void ControlPDMotorControlData::read_from_xmlrpc_value( - const std::string &prefix) { + const std::string& prefix) { pid_controller.initParam(prefix); } @@ -98,13 +98,13 @@ RCSotController::~RCSotController() { } void RCSotController::displayClaimedResources( - ClaimedResources &claimed_resources) { + ClaimedResources& claimed_resources) { #ifdef CONTROLLER_INTERFACE_KINETIC 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; + hardware_interface::InterfaceResources& aclaim = *it_claim; ROS_INFO_STREAM( "Claimed by RCSotController: " << aclaim.hardware_interface); @@ -124,7 +124,7 @@ void RCSotController::displayClaimedResources( #endif } -void RCSotController::initLogs(ros::NodeHandle &robot_nh) { +void RCSotController::initLogs(ros::NodeHandle& robot_nh) { ROS_INFO_STREAM("Initialize log data structure"); int length = 300000; @@ -153,10 +153,10 @@ void RCSotController::initLogs(ros::NodeHandle &robot_nh) { LoggerStreamPtr_t(new LoggerROSStream())); } -bool RCSotController::initRequest(lhi::RobotHW *robot_hw, - ros::NodeHandle &robot_nh, - ros::NodeHandle &controller_nh, - ClaimedResources &claimed_resources) { +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 if (!readParams(robot_nh)) return false; @@ -176,9 +176,9 @@ bool RCSotController::initRequest(lhi::RobotHW *robot_hw, return true; } -bool RCSotController::initInterfaces(lhi::RobotHW *robot_hw, ros::NodeHandle &, - ros::NodeHandle &, - ClaimedResources &claimed_resources) { +bool RCSotController::initInterfaces(lhi::RobotHW* robot_hw, ros::NodeHandle&, + ros::NodeHandle&, + ClaimedResources& claimed_resources) { std::string lns; lns = "hardware_interface"; @@ -349,7 +349,7 @@ bool RCSotController::init() { // Initialize ros node. int argc = 1; - char *argv[1]; + char* argv[1]; argv[0] = new char[10]; strcpy(argv[0], "libsot"); SotLoaderBasic::initializeRosNode(argc, argv); @@ -357,7 +357,7 @@ bool RCSotController::init() { return true; } -void RCSotController::readParamsVerbosityLevel(ros::NodeHandle &robot_nh) { +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_); @@ -370,7 +370,7 @@ void RCSotController::readParamsVerbosityLevel(ros::NodeHandle &robot_nh) { } } -bool RCSotController::readParamsSotLibName(ros::NodeHandle &robot_nh) { +bool RCSotController::readParamsSotLibName(ros::NodeHandle& robot_nh) { // Read param to find the library to load std::string dynamic_library_name; @@ -393,12 +393,12 @@ bool RCSotController::readParamsSotLibName(ros::NodeHandle &robot_nh) { return true; } -bool RCSotController::readParamsPositionControlData(ros::NodeHandle &) { +bool RCSotController::readParamsPositionControlData(ros::NodeHandle&) { return false; } bool RCSotController::readParamsEffortControlPDMotorControlData( - ros::NodeHandle &robot_nh) { + ros::NodeHandle& robot_nh) { // Read libname if (robot_nh.hasParam("/sot_controller/effort_control_pd_motor_init/gains")) { XmlRpc::XmlRpcValue xml_rpc_ecpd_init; @@ -444,7 +444,7 @@ bool RCSotController::readParamsEffortControlPDMotorControlData( } bool RCSotController::readParamsVelocityControlPDMotorControlData( - ros::NodeHandle &robot_nh) { + ros::NodeHandle& robot_nh) { // Read libname if (robot_nh.hasParam("/sot_controller/velocity_control_pd_motor_init/" "gains")) { @@ -491,7 +491,7 @@ bool RCSotController::readParamsVelocityControlPDMotorControlData( return false; } -bool RCSotController::readParamsFromRCToSotDevice(ros::NodeHandle &robot_nh) { +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", @@ -519,7 +519,7 @@ bool RCSotController::readParamsFromRCToSotDevice(ros::NodeHandle &robot_nh) { return true; } -bool RCSotController::readParamsJointNames(ros::NodeHandle &robot_nh) { +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 @@ -557,8 +557,8 @@ bool RCSotController::readParamsJointNames(ros::NodeHandle &robot_nh) { return true; } -bool RCSotController::getJointControlMode(std::string &joint_name, - JointSotHandle &aJointSotHandle) { +bool RCSotController::getJointControlMode(std::string& joint_name, + JointSotHandle& aJointSotHandle) { std::string scontrol_mode; static const std::string seffort("EFFORT"), svelocity("VELOCITY"), sposition("POSITION"); @@ -593,7 +593,7 @@ bool RCSotController::getJointControlMode(std::string &joint_name, return true; } -bool RCSotController::readParamsControlMode(ros::NodeHandle &robot_nh) { +bool RCSotController::readParamsControlMode(ros::NodeHandle& robot_nh) { std::map mapControlMode; // Read param from control_mode. @@ -601,7 +601,7 @@ bool RCSotController::readParamsControlMode(ros::NodeHandle &robot_nh) { /// 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]; + JointSotHandle& aJoint = joints_[joint_name]; if (!getJointControlMode(joint_name, aJoint)) return false; ROS_INFO("joint_name[%d]=%s, control_mode=%d", idJoint, joint_name.c_str(), aJoint.ros_control_mode); @@ -613,7 +613,7 @@ bool RCSotController::readParamsControlMode(ros::NodeHandle &robot_nh) { return true; } -bool RCSotController::readParamsdt(ros::NodeHandle &robot_nh) { +bool RCSotController::readParamsdt(ros::NodeHandle& robot_nh) { // Get subsampling ratio of the stack of task: sot period / roscontrol period // If param does not exist default value is 1 robot_nh.getParam("/sot_controller/subsampling", subSampling_); @@ -628,7 +628,7 @@ bool RCSotController::readParamsdt(ros::NodeHandle &robot_nh) { return false; } -bool RCSotController::readUrdf(ros::NodeHandle &robot_nh) { +bool RCSotController::readUrdf(ros::NodeHandle& robot_nh) { /// Reading the parameter /robot_description which contains the robot /// description if (!robot_nh.hasParam("/robot_description")) { @@ -645,7 +645,7 @@ bool RCSotController::readUrdf(ros::NodeHandle &robot_nh) { return true; } -bool RCSotController::readParams(ros::NodeHandle &robot_nh) { +bool RCSotController::readParams(ros::NodeHandle& robot_nh) { /// Read the level of verbosity for the controller /// (0: quiet, 1: info, 2: debug). /// Default to quiet @@ -692,9 +692,9 @@ bool RCSotController::initJoints() { bool notok = true; while (notok) { - std::string &joint_name = joints_name_[i]; + std::string& joint_name = joints_name_[i]; try { - JointSotHandle &aJointSotHandle = joints_[joint_name]; + JointSotHandle& aJointSotHandle = joints_[joint_name]; switch (aJointSotHandle.ros_control_mode) { case POSITION: aJointSotHandle.joint = pos_iface_->getHandle(joint_name); @@ -736,7 +736,7 @@ bool RCSotController::initIMU() { if (!imu_iface_) return false; // get all imu sensor names - const std ::vector &imu_iface_names = imu_iface_->getNames(); + const std ::vector& 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()); @@ -753,7 +753,7 @@ bool RCSotController::initForceSensors() { if (!ft_iface_) return false; // get force torque sensors names package. - const std::vector &ft_iface_names = ft_iface_->getNames(); + const std::vector& 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()); @@ -772,7 +772,7 @@ bool RCSotController::initTemperatureSensors() { if (!act_temp_iface_) return false; // get temperature sensors names - const std::vector &act_temp_iface_names = + const std::vector& act_temp_iface_names = act_temp_iface_->getNames(); if (verbosity_level_ > 0) { @@ -794,8 +794,8 @@ bool RCSotController::initTemperatureSensors() { return true; } -void RCSotController::fillSensorsIn(std::string &title, - std::vector &data) { +void RCSotController::fillSensorsIn(std::string& title, + std::vector& data) { /// Tries to find the mapping from the local validation /// to the SoT device. it_map_rt_to_sot it_mapRC2Sot = mapFromRCToSotDevice_.find(title); @@ -813,7 +813,7 @@ void RCSotController::fillJoints() { 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; + JointSotHandle& aJoint = anItJoint->second; DataOneIter_.motor_angle[idJoint] = aJoint.joint.getPosition(); #ifdef TEMPERATURE_SENSOR_CONTROLLER @@ -841,8 +841,8 @@ void RCSotController::fillJoints() { fillSensorsIn(ltitle, DataOneIter_.motor_currents); } -void RCSotController::setSensorsImu(std::string &name, int IMUnb, - std::vector &data) { +void RCSotController::setSensorsImu(std::string& name, int IMUnb, + std::vector& data) { std::ostringstream labelOss; labelOss << name << IMUnb; std::string label_s = labelOss.str(); @@ -920,13 +920,13 @@ void RCSotController::fillSensors() { } void RCSotController::readControl( - std::map &controlValues) { + std::map& 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; + std::string& lmapRC2Sot = it_mapRC2Sot->second; command_ = controlValues[lmapRC2Sot].getValues(); ODEBUG4("angleControl_.size() = " << command_.size()); for (unsigned int i = 0; i < std::min(command_.size(), joints_.size()); @@ -943,7 +943,7 @@ void RCSotController::readControl( } } -void RCSotController::one_iteration(const ros::Duration &period) { +void RCSotController::one_iteration(const ros::Duration& period) { sotComputing_ = true; // Chrono start RcSotLog_.start_it(); @@ -954,7 +954,7 @@ void RCSotController::one_iteration(const ros::Duration &period) { /// Generate a control law. try { sotController_->nominalSetSensors(sensorsIn_); - } catch (std::exception &e) { + } catch (std::exception& e) { std::cerr << "Failure happened during one_iteration(): " << "when calling nominalSetSensors " << std::endl; std::cerr << __FILE__ << " " << __LINE__ << std::endl @@ -964,7 +964,7 @@ void RCSotController::one_iteration(const ros::Duration &period) { } try { sotController_->getControl(controlValues_copy_, period.toSec()); - } catch (std::exception &e) { + } catch (std::exception& e) { std::cerr << "Failure happened during one_iteration(): " << "when calling getControl " << std::endl; std::cerr << __FILE__ << " " << __LINE__ << std::endl @@ -993,7 +993,7 @@ void RCSotController::one_iteration(const ros::Duration &period) { } void RCSotController::localStandbyEffortControlMode( - const ros::Duration &period) { + 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++) { @@ -1002,9 +1002,9 @@ void RCSotController::localStandbyEffortControlMode( 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; + 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(); @@ -1018,7 +1018,7 @@ void RCSotController::localStandbyEffortControlMode( } void RCSotController::localStandbyVelocityControlMode( - const ros::Duration &period) { + const ros::Duration& period) { static bool first_time = true; /// Iterate over all the joints @@ -1029,9 +1029,9 @@ void RCSotController::localStandbyVelocityControlMode( 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; + 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(); @@ -1062,8 +1062,8 @@ void RCSotController::localStandbyPositionControlMode() { // If it is position mode control. if (joints_[joint_name].ros_control_mode == POSITION) { - JointSotHandle &aJointSotHandle = joints_[joint_name]; - lhi::JointHandle &aJoint = aJointSotHandle.joint; + JointSotHandle& aJointSotHandle = joints_[joint_name]; + lhi::JointHandle& aJoint = aJointSotHandle.joint; aJoint.setCommand(aJointSotHandle.desired_init_pose); @@ -1092,7 +1092,7 @@ void RCSotController::computeSubSampling() { thread_created_ = true; } } -void RCSotController::update(const ros::Time &, const ros::Duration &period) { +void RCSotController::update(const ros::Time&, const ros::Duration& period) { // Do not send any control if the dynamic graph is not started if (!isDynamicGraphStopped()) { // Increment step at beginning of this method since the end time may @@ -1129,7 +1129,7 @@ void RCSotController::update(const ros::Time &, const ros::Duration &period) { // controlled in position. if (controlValues_.find("velocity") != controlValues_.end()) { std::vector control = controlValues_["control"].getValues(); - const std::vector &velocity = + const std::vector& velocity = controlValues_["velocity"].getValues(); for (std::size_t i = 0; i < control.size(); ++i) { control[i] += period.toSec() * velocity[i]; @@ -1142,7 +1142,7 @@ void RCSotController::update(const ros::Time &, const ros::Duration &period) { } } - } catch (std::exception const &exc) { + } catch (std::exception const& exc) { ROS_ERROR_STREAM("Failure happened during one_iteration evaluation: " << exc.what() << "\nUse gdb to investiguate the problem\n" @@ -1161,7 +1161,7 @@ void RCSotController::update(const ros::Time &, const ros::Duration &period) { fillSensors(); try { sotController_->setupSetSensors(sensorsIn_); - } catch (std::exception &e) { + } catch (std::exception& e) { ROS_ERROR_STREAM("RCSotController::update: " << e.what()); throw; } @@ -1174,12 +1174,12 @@ void RCSotController::update(const ros::Time &, const ros::Duration &period) { } } -void RCSotController::starting(const ros::Time &) { +void RCSotController::starting(const ros::Time&) { using namespace ::dynamicgraph; fillSensors(); } -void RCSotController::stopping(const ros::Time &) {} +void RCSotController::stopping(const ros::Time&) {} PLUGINLIB_EXPORT_CLASS(sot_controller::RCSotController, lci::ControllerBase) } // namespace sot_controller diff --git a/src/roscontrol-sot-controller.hh b/src/roscontrol-sot-controller.hh index 84a656d..66dd1e4 100644 --- a/src/roscontrol-sot-controller.hh +++ b/src/roscontrol-sot-controller.hh @@ -39,7 +39,7 @@ namespace lci = controller_interface; class XmlrpcHelperException : public ros::Exception { public: - XmlrpcHelperException(const std::string &what) : ros::Exception(what) {} + XmlrpcHelperException(const std::string& what) : ros::Exception(what) {} }; struct ControlPDMotorControlData { @@ -47,7 +47,7 @@ struct ControlPDMotorControlData { ControlPDMotorControlData(); // void read_from_xmlrpc_value(XmlRpc::XmlRpcValue &aXRV); - void read_from_xmlrpc_value(const std::string &prefix); + void read_from_xmlrpc_value(const std::string& prefix); }; struct JointSotHandle { @@ -97,23 +97,23 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { #endif /// \brief Interface to the joints controlled in position. - lhi::PositionJointInterface *pos_iface_; + lhi::PositionJointInterface* pos_iface_; /// \brief Interface to the joints controlled in position. - lhi::VelocityJointInterface *vel_iface_; + lhi::VelocityJointInterface* vel_iface_; /// \brief Interface to the joints controlled in force. - lhi::EffortJointInterface *effort_iface_; + lhi::EffortJointInterface* effort_iface_; /// \brief Interface to the sensors (IMU). - lhi::ImuSensorInterface *imu_iface_; + lhi::ImuSensorInterface* imu_iface_; /// \brief Interface to the sensors (Force). - lhi::ForceTorqueSensorInterface *ft_iface_; + lhi::ForceTorqueSensorInterface* ft_iface_; #ifdef TEMPERATURE_SENSOR_CONTROLLER /// \brief Interface to the actuator temperature sensor. - lhi::ActuatorTemperatureSensorInterface *act_temp_iface_; + lhi::ActuatorTemperatureSensorInterface* act_temp_iface_; #endif /// @} @@ -177,12 +177,12 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { /// \brief Read the configuration files, /// claims the request to the robot and initialize the Stack-Of-Tasks. - bool initRequest(lhi::RobotHW *robot_hw, ros::NodeHandle &robot_nh, - ros::NodeHandle &controller_nh, - ClaimedResources &claimed_resources); + bool initRequest(lhi::RobotHW* robot_hw, ros::NodeHandle& robot_nh, + ros::NodeHandle& controller_nh, + ClaimedResources& claimed_resources); /// \brief Display claimed resources - void displayClaimedResources(ClaimedResources &claimed_resources); + void displayClaimedResources(ClaimedResources& claimed_resources); /// \brief Claims bool init(); @@ -190,16 +190,16 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { /// \brief Read the sensor values, calls the control graph, and apply the /// control. /// - void update(const ros::Time &, const ros::Duration &); + void update(const ros::Time&, const ros::Duration&); /// \brief Starting by filling the sensors. - void starting(const ros::Time &); + void starting(const ros::Time&); /// \brief Stopping the control - void stopping(const ros::Time &); + void stopping(const ros::Time&); protected: /// Initialize the roscontrol interfaces - bool initInterfaces(lhi::RobotHW *robot_hw, ros::NodeHandle &, - ros::NodeHandle &, ClaimedResources &claimed_resources); + bool initInterfaces(lhi::RobotHW* robot_hw, ros::NodeHandle&, + ros::NodeHandle&, ClaimedResources& claimed_resources); /// Initialize the hardware interface using the joints. bool initJoints(); @@ -212,52 +212,52 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { /// Initialize internal structure for the logs based on nbDofs /// number of force sensors and size of the buffer. - void initLogs(ros::NodeHandle &robot_nh); + void initLogs(ros::NodeHandle& robot_nh); ///@{ \name Read the parameter server /// \brief Entry point - bool readParams(ros::NodeHandle &robot_nh); + bool readParams(ros::NodeHandle& robot_nh); /// \brief Creates the list of joint names. - bool readParamsJointNames(ros::NodeHandle &robot_nh); + bool readParamsJointNames(ros::NodeHandle& robot_nh); /// \brief Set the SoT library name. - bool readParamsSotLibName(ros::NodeHandle &robot_nh); + bool readParamsSotLibName(ros::NodeHandle& robot_nh); /// \Brief Set the mapping between ros-control and the robot device /// For instance the yaml file should have a line with map_rc_to_sot_device: /// map_rc_to_sot_device: [ ] - bool readParamsFromRCToSotDevice(ros::NodeHandle &robot_nh); + bool readParamsFromRCToSotDevice(ros::NodeHandle& robot_nh); /// \brief Read the control mode. - bool readParamsControlMode(ros::NodeHandle &robot_nh); + bool readParamsControlMode(ros::NodeHandle& robot_nh); /// \brief Read the PID information of the robot in velocity mode. - bool readParamsVelocityControlPDMotorControlData(ros::NodeHandle &robot_nh); + bool readParamsVelocityControlPDMotorControlData(ros::NodeHandle& robot_nh); /// \brief Read the PID information of the robot in effort mode. - bool readParamsEffortControlPDMotorControlData(ros::NodeHandle &robot_nh); + bool readParamsEffortControlPDMotorControlData(ros::NodeHandle& robot_nh); /// \brief Read the desired initial pose of the robot in position mode. - bool readParamsPositionControlData(ros::NodeHandle &robot_nh); + bool readParamsPositionControlData(ros::NodeHandle& robot_nh); /// \brief Read the control period. - bool readParamsdt(ros::NodeHandle &robot_nh); + bool readParamsdt(ros::NodeHandle& robot_nh); /// \brief Read verbosity level to display messages mostly during /// initialization - void readParamsVerbosityLevel(ros::NodeHandle &robot_nh); + void readParamsVerbosityLevel(ros::NodeHandle& robot_nh); ///@} /// \brief Fill the SoT map structures - void fillSensorsIn(std::string &title, std::vector &data); + void fillSensorsIn(std::string& title, std::vector& data); /// \brief Get the information from the low level and calls fillSensorsIn. void fillJoints(); /// In the map sensorsIn_ creates the key "name_IMUNb" /// and associate to this key the vector data. - void setSensorsImu(std::string &name, int IMUNb, std::vector &data); + void setSensorsImu(std::string& name, int IMUNb, std::vector& data); /// @{ \name Fill the sensors /// Read the imus and set the interface to the SoT. @@ -272,9 +272,9 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { ///@{ Control the robot while waiting for the SoT /// Default control in effort. - void localStandbyEffortControlMode(const ros::Duration &period); + void localStandbyEffortControlMode(const ros::Duration& period); /// Default control in velocity. - void localStandbyVelocityControlMode(const ros::Duration &period); + void localStandbyVelocityControlMode(const ros::Duration& period); /// Default control in position. void localStandbyPositionControlMode(); @@ -283,7 +283,7 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { /// \param controlValues map string to vector of double. The function will /// fill in /// controlValues["control"] - void readControl(std::map &controlValues); + void readControl(std::map& controlValues); /// Map of sensor readings std::map sensorsIn_; @@ -303,16 +303,16 @@ class RCSotController : public lci::ControllerBase, SotLoaderBasic { /// One iteration: read sensor, compute the control law, apply control. /// \param period time since last call. Useful when realtime is not enforced /// correctly. - void one_iteration(const ros::Duration &period); + void one_iteration(const ros::Duration& period); /// Read URDF model from /robot_description parameter. - bool readUrdf(ros::NodeHandle &robot_nh); + bool readUrdf(ros::NodeHandle& robot_nh); /// Returns control mode by reading rosparam. /// It reads /sot_controller/control_mode/joint_name /// and check - bool getJointControlMode(std::string &joint_name, - JointSotHandle &aJointSotHandle); + bool getJointControlMode(std::string& joint_name, + JointSotHandle& aJointSotHandle); }; } // namespace sot_controller diff --git a/src/roscontrol-sot-parse-log.cc b/src/roscontrol-sot-parse-log.cc index 657d91b..6c4e9c9 100644 --- a/src/roscontrol-sot-parse-log.cc +++ b/src/roscontrol-sot-parse-log.cc @@ -4,11 +4,11 @@ #include #include -void usage(char *bin) { +void usage(char* bin) { std::cerr << "Usage: " << bin << " [--separator sep] binary_file_name\n"; } -int main(int argc, char *argv[]) { +int main(int argc, char* argv[]) { if (argc < 2) { usage(argv[0]); return 1; @@ -34,8 +34,8 @@ int main(int argc, char *argv[]) { // Read headers std::size_t nVector = 0, vectorSize = 0; - in.read((char *)&nVector, sizeof(std::size_t)); - in.read((char *)&vectorSize, sizeof(std::size_t)); + in.read((char*)&nVector, sizeof(std::size_t)); + in.read((char*)&vectorSize, sizeof(std::size_t)); if (!in.good()) { std::cerr << "Couldn't parse file: " << argv[iarg] << '\n'; return 3; @@ -47,7 +47,7 @@ int main(int argc, char *argv[]) { for (std::size_t i = 0; i < nVector; ++i) { for (std::size_t j = 0; j < vectorSize; ++j) { - in.read((char *)&v, sizeof(double)); + in.read((char*)&v, sizeof(double)); if (!in.good()) { std::cerr << "Stopped to parse at (" << i << ',' << j << ") of file: " << argv[iarg] << '\n'; diff --git a/tests/roscontrol_sot_hardware.cpp b/tests/roscontrol_sot_hardware.cpp index 0b43a29..b290a7b 100644 --- a/tests/roscontrol_sot_hardware.cpp +++ b/tests/roscontrol_sot_hardware.cpp @@ -9,7 +9,7 @@ #include // Threads -void *RTloop(void *argument); +void* RTloop(void* argument); pthread_mutex_t mutx = PTHREAD_MUTEX_INITIALIZER; // mutex initialisation //****************************************************** @@ -181,14 +181,14 @@ int TestRobot01Class::UpdateCmd() { } typedef struct arg_struct { - controller_manager::ControllerManager *cm; - TestRobot01Class *testrobot01; + controller_manager::ControllerManager* cm; + TestRobot01Class* testrobot01; } RTloopArgs; -void *RTloop(void *argument) { +void* RTloop(void* argument) { ROS_INFO("IN thread1 OK"); - RTloopArgs *aRTloopArgs; - aRTloopArgs = (RTloopArgs *)argument; + RTloopArgs* aRTloopArgs; + aRTloopArgs = (RTloopArgs*)argument; ros::Time last_time = ros::Time::now(); @@ -234,7 +234,7 @@ void *RTloop(void *argument) { pthread_exit(EXIT_SUCCESS); } -int main(int argc, char *argv[]) { +int main(int argc, char* argv[]) { TestRobot01Class testrobot01; /*---------------- ROS Stuff ------------------ */ @@ -259,7 +259,7 @@ int main(int argc, char *argv[]) { // function sets the scheduling policy and parameters of the thread error_return = pthread_create(&thread1, NULL, RTloop, - (void *)&aRTloopArgs); // create a new thread + (void*)&aRTloopArgs); // create a new thread ROS_INFO("thread1 created OK"); if (error_return) { diff --git a/tests/sot-test-controller.cpp b/tests/sot-test-controller.cpp index 19d7886..d194f90 100644 --- a/tests/sot-test-controller.cpp +++ b/tests/sot-test-controller.cpp @@ -35,7 +35,7 @@ boost::condition_variable cond; boost::mutex mut; bool data_ready; -void workThread(SoTTestController *aSoTTest) { +void workThread(SoTTestController* aSoTTest) { dynamicgraph::Interpreter aLocalInterpreter( dynamicgraph::rosInit(false, true)); @@ -74,34 +74,34 @@ void SoTTestController::init() { SoTTestController::~SoTTestController() {} void SoTTestController::setupSetSensors( - map &SensorsIn) { + map& SensorsIn) { device_->setupSetSensors(SensorsIn); } void SoTTestController::nominalSetSensors( - map &SensorsIn) { + map& SensorsIn) { device_->nominalSetSensors(SensorsIn); } void SoTTestController::cleanupSetSensors( - map &SensorsIn) { + map& SensorsIn) { device_->cleanupSetSensors(SensorsIn); } void SoTTestController::getControl( - map &controlOut, const double &period) { + map& controlOut, const double& period) { try { sotDEBUG(25) << __FILE__ << __FUNCTION__ << "(#" << __LINE__ << ")" << endl; device_->getControl(controlOut, period); sotDEBUG(25) << __FILE__ << __FUNCTION__ << "(#" << __LINE__ << ")" << endl; - } catch (dynamicgraph::sot::ExceptionAbstract &err) { + } catch (dynamicgraph::sot::ExceptionAbstract& err) { std::cout << __FILE__ << " " << __FUNCTION__ << " (" << __LINE__ << ") " << err.getStringMessage() << endl; throw err; } } -void SoTTestController::setControlSize(const size_type &size) { +void SoTTestController::setControlSize(const size_type& size) { device_->setControlSize(size); } @@ -113,9 +113,9 @@ void SoTTestController::setSecondOrderIntegration(void) { device_->setSecondOrderIntegration(); } -void SoTTestController::runPython(std::ostream &file, - const std::string &command, - dynamicgraph::Interpreter &interpreter) { +void SoTTestController::runPython(std::ostream& file, + const std::string& command, + dynamicgraph::Interpreter& interpreter) { file << ">>> " << command << std::endl; std::string lerr(""), lout(""), lres(""); interpreter.runCommand(command, lres, lout, lerr); @@ -151,7 +151,7 @@ void SoTTestController::startupPython() { } extern "C" { -dgsot::AbstractSotExternalInterface *createSotExternalInterface() { +dgsot::AbstractSotExternalInterface* createSotExternalInterface() { return new SoTTestController("test_robot"); } } diff --git a/tests/sot-test-controller.hh b/tests/sot-test-controller.hh index 8f11e94..7fae7e6 100644 --- a/tests/sot-test-controller.hh +++ b/tests/sot-test-controller.hh @@ -33,16 +33,16 @@ class SoTTestController : public dgsot::AbstractSotExternalInterface { SoTTestController(std::string robotName); virtual ~SoTTestController(); - void setupSetSensors(std::map &sensorsIn); + void setupSetSensors(std::map& sensorsIn); - void nominalSetSensors(std::map &sensorsIn); + void nominalSetSensors(std::map& sensorsIn); - void cleanupSetSensors(std::map &sensorsIn); + void cleanupSetSensors(std::map& sensorsIn); - void getControl(std::map &anglesOut, - const double &period); + void getControl(std::map& anglesOut, + const double& period); - void setControlSize(const size_type &size); + void setControlSize(const size_type& size); void initialize(); void setNoIntegration(void); void setSecondOrderIntegration(void); @@ -53,16 +53,16 @@ class SoTTestController : public dgsot::AbstractSotExternalInterface { protected: // Update output port with the control computed from the // dynamic graph. - void updateRobotState(std::vector &anglesIn); + void updateRobotState(std::vector& anglesIn); - void runPython(std::ostream &file, const std::string &command, - dynamicgraph::Interpreter &interpreter); + void runPython(std::ostream& file, const std::string& command, + dynamicgraph::Interpreter& interpreter); virtual void startupPython(); void init(); - SoTTestDevice *device_; + SoTTestDevice* device_; }; #endif /* _SOT_TestController_H_ */ diff --git a/tests/sot-test-device.cpp b/tests/sot-test-device.cpp index f9b7c5b..d0349a7 100644 --- a/tests/sot-test-device.cpp +++ b/tests/sot-test-device.cpp @@ -106,7 +106,7 @@ SoTTestDevice::SoTTestDevice(std::string RobotName) SoTTestDevice::~SoTTestDevice() {} -void SoTTestDevice::setSensorsForce(map &SensorsIn, +void SoTTestDevice::setSensorsForce(map& SensorsIn, sigtime_t t) { int map_sot_2_urdf[4] = {2, 0, 3, 1}; sotDEBUGIN(15); @@ -114,7 +114,7 @@ void SoTTestDevice::setSensorsForce(map &SensorsIn, it = SensorsIn.find("forces"); if (it != SensorsIn.end()) { // Implements force recollection. - const vector &forcesIn = it->second.getValues(); + const vector& forcesIn = it->second.getValues(); if (forcesIn.size() != 0) { for (int i = 0; i < 4; ++i) { sotDEBUG(15) << "Force sensor " << i << std::endl; @@ -132,13 +132,13 @@ void SoTTestDevice::setSensorsForce(map &SensorsIn, sotDEBUGIN(15); } -void SoTTestDevice::setSensorsIMU(map &SensorsIn, +void SoTTestDevice::setSensorsIMU(map& SensorsIn, sigtime_t t) { map::iterator it; // TODO: Confirm if this can be made quaternion it = SensorsIn.find("attitude"); if (it != SensorsIn.end()) { - const vector &attitude = it->second.getValues(); + const vector& attitude = it->second.getValues(); for (unsigned int i = 0; i < 3; ++i) for (unsigned int j = 0; j < 3; ++j) pose(i, j) = attitude[i * 3 + j]; attitudeSOUT.setConstant(pose); @@ -147,7 +147,7 @@ void SoTTestDevice::setSensorsIMU(map &SensorsIn, it = SensorsIn.find("accelerometer_0"); if (it != SensorsIn.end()) { - const vector &accelerometer = + const vector& accelerometer = SensorsIn["accelerometer_0"].getValues(); for (std::size_t i = 0; i < 3; ++i) accelerometer_(i) = accelerometer[i]; accelerometerSOUT_.setConstant(accelerometer_); @@ -156,7 +156,7 @@ void SoTTestDevice::setSensorsIMU(map &SensorsIn, it = SensorsIn.find("gyrometer_0"); if (it != SensorsIn.end()) { - const vector &gyrometer = SensorsIn["gyrometer_0"].getValues(); + const vector& gyrometer = SensorsIn["gyrometer_0"].getValues(); for (std::size_t i = 0; i < 3; ++i) gyrometer_(i) = gyrometer[i]; gyrometerSOUT_.setConstant(gyrometer_); gyrometerSOUT_.setTime(t); @@ -164,12 +164,12 @@ void SoTTestDevice::setSensorsIMU(map &SensorsIn, } void SoTTestDevice::setSensorsEncoders( - map &SensorsIn, sigtime_t t) { + map& SensorsIn, sigtime_t t) { map::iterator it; it = SensorsIn.find("motor-angles"); if (it != SensorsIn.end()) { - const vector &anglesIn = it->second.getValues(); + const vector& anglesIn = it->second.getValues(); dgRobotState_.resize(anglesIn.size() + 6); motor_angles_.resize(anglesIn.size()); for (unsigned i = 0; i < 6; ++i) dgRobotState_(i) = 0.; @@ -185,7 +185,7 @@ void SoTTestDevice::setSensorsEncoders( it = SensorsIn.find("joint-angles"); if (it != SensorsIn.end()) { - const vector &joint_anglesIn = it->second.getValues(); + const vector& joint_anglesIn = it->second.getValues(); joint_angles_.resize(joint_anglesIn.size()); for (unsigned i = 0; i < joint_anglesIn.size(); ++i) joint_angles_(i) = joint_anglesIn[i]; @@ -195,12 +195,12 @@ void SoTTestDevice::setSensorsEncoders( } void SoTTestDevice::setSensorsVelocities( - map &SensorsIn, sigtime_t t) { + map& SensorsIn, sigtime_t t) { map::iterator it; it = SensorsIn.find("velocities"); if (it != SensorsIn.end()) { - const vector &velocitiesIn = it->second.getValues(); + const vector& velocitiesIn = it->second.getValues(); dgRobotVelocity_.resize(velocitiesIn.size() + 6); for (unsigned i = 0; i < 6; ++i) dgRobotVelocity_(i) = 0.; for (unsigned i = 0; i < velocitiesIn.size(); ++i) { @@ -212,11 +212,11 @@ void SoTTestDevice::setSensorsVelocities( } void SoTTestDevice::setSensorsTorquesCurrents( - map &SensorsIn, sigtime_t t) { + map& SensorsIn, sigtime_t t) { map::iterator it; it = SensorsIn.find("torques"); if (it != SensorsIn.end()) { - const std::vector &torques = SensorsIn["torques"].getValues(); + const std::vector& torques = SensorsIn["torques"].getValues(); torques_.resize(torques.size()); for (std::size_t i = 0; i < torques.size(); ++i) torques_(i) = torques[i]; pseudoTorqueSOUT.setConstant(torques_); @@ -225,7 +225,7 @@ void SoTTestDevice::setSensorsTorquesCurrents( it = SensorsIn.find("currents"); if (it != SensorsIn.end()) { - const std::vector ¤ts = SensorsIn["currents"].getValues(); + const std::vector& currents = SensorsIn["currents"].getValues(); currents_.resize(currents.size()); for (std::size_t i = 0; i < currents.size(); ++i) currents_(i) = currents[i]; @@ -234,12 +234,12 @@ void SoTTestDevice::setSensorsTorquesCurrents( } } -void SoTTestDevice::setSensorsGains(map &SensorsIn, +void SoTTestDevice::setSensorsGains(map& SensorsIn, sigtime_t t) { map::iterator it; it = SensorsIn.find("p_gains"); if (it != SensorsIn.end()) { - const std::vector &p_gains = SensorsIn["p_gains"].getValues(); + const std::vector& p_gains = SensorsIn["p_gains"].getValues(); p_gains_.resize(p_gains.size()); for (std::size_t i = 0; i < p_gains.size(); ++i) p_gains_(i) = p_gains[i]; p_gainsSOUT_.setConstant(p_gains_); @@ -248,7 +248,7 @@ void SoTTestDevice::setSensorsGains(map &SensorsIn, it = SensorsIn.find("d_gains"); if (it != SensorsIn.end()) { - const std::vector &d_gains = SensorsIn["d_gains"].getValues(); + const std::vector& d_gains = SensorsIn["d_gains"].getValues(); d_gains_.resize(d_gains.size()); for (std::size_t i = 0; i < d_gains.size(); ++i) d_gains_(i) = d_gains[i]; d_gainsSOUT_.setConstant(d_gains_); @@ -256,7 +256,7 @@ void SoTTestDevice::setSensorsGains(map &SensorsIn, } } -void SoTTestDevice::setSensors(map &SensorsIn) { +void SoTTestDevice::setSensors(map& SensorsIn) { sotDEBUGIN(25); map::iterator it; sigtime_t t = stateSOUT.getTime() + 1; @@ -272,22 +272,22 @@ void SoTTestDevice::setSensors(map &SensorsIn) { } void SoTTestDevice::setupSetSensors( - map &SensorsIn) { + map& SensorsIn) { setSensors(SensorsIn); } void SoTTestDevice::nominalSetSensors( - map &SensorsIn) { + map& SensorsIn) { setSensors(SensorsIn); } void SoTTestDevice::cleanupSetSensors( - map &SensorsIn) { + map& SensorsIn) { setSensors(SensorsIn); } -void SoTTestDevice::getControl(map &controlOut, - const double &) { +void SoTTestDevice::getControl(map& controlOut, + const double&) { ODEBUG5FULL("start"); sotDEBUGIN(25); vector anglesOut; @@ -327,18 +327,18 @@ using namespace dynamicgraph::sot; namespace dynamicgraph { namespace sot { #ifdef WIN32 -const char *DebugTrace::DEBUG_FILENAME_DEFAULT = "c:/tmp/sot-core-traces.txt"; +const char* DebugTrace::DEBUG_FILENAME_DEFAULT = "c:/tmp/sot-core-traces.txt"; #else // WIN32 -const char *DebugTrace::DEBUG_FILENAME_DEFAULT = "/tmp/sot-core-traces.txt"; +const char* DebugTrace::DEBUG_FILENAME_DEFAULT = "/tmp/sot-core-traces.txt"; #endif // WIN32 #ifdef VP_DEBUG #ifdef WIN32 std::ofstream debugfile("C:/tmp/sot-core-traces.txt", - std::ios::trunc &std::ios::out); + std::ios::trunc& std::ios::out); #else // WIN32 std::ofstream debugfile("/tmp/sot-core-traces.txt", - std::ios::trunc &std::ios::out); + std::ios::trunc& std::ios::out); #endif // WIN32 #else // VP_DEBUG diff --git a/tests/sot-test-device.hh b/tests/sot-test-device.hh index 38cbf8c..5f5105e 100644 --- a/tests/sot-test-device.hh +++ b/tests/sot-test-device.hh @@ -29,21 +29,21 @@ class SoTTestDevice : public dgsot::Device { static const std::string CLASS_NAME; static const double TIMESTEP_DEFAULT; - virtual const std::string &getClassName() const { return CLASS_NAME; } + virtual const std::string& getClassName() const { return CLASS_NAME; } SoTTestDevice(std::string RobotName); virtual ~SoTTestDevice(); - void setSensors(std::map &sensorsIn); + void setSensors(std::map& sensorsIn); - void setupSetSensors(std::map &sensorsIn); + void setupSetSensors(std::map& sensorsIn); - void nominalSetSensors(std::map &sensorsIn); + void nominalSetSensors(std::map& sensorsIn); - void cleanupSetSensors(std::map &sensorsIn); + void cleanupSetSensors(std::map& sensorsIn); - void getControl(std::map &anglesOut, - const double &period); + void getControl(std::map& anglesOut, + const double& period); void timeStep(double ts) { timestep_ = ts; } @@ -71,17 +71,17 @@ class SoTTestDevice : public dgsot::Device { dynamicgraph::Signal d_gainsSOUT_; /// Protected methods for internal variables filling - void setSensorsForce(std::map &SensorsIn, + void setSensorsForce(std::map& SensorsIn, sigtime_t t); - void setSensorsIMU(std::map &SensorsIn, + void setSensorsIMU(std::map& SensorsIn, sigtime_t t); - void setSensorsEncoders(std::map &SensorsIn, + void setSensorsEncoders(std::map& SensorsIn, sigtime_t t); void setSensorsVelocities( - std::map &SensorsIn, sigtime_t t); + std::map& SensorsIn, sigtime_t t); void setSensorsTorquesCurrents( - std::map &SensorsIn, sigtime_t t); - void setSensorsGains(std::map &SensorsIn, + std::map& SensorsIn, sigtime_t t); + void setSensorsGains(std::map& SensorsIn, sigtime_t t); /// Intermediate variables to avoid allocation during control