31 #include <boost/foreach.hpp> 38 #include <controller_manager_msgs/ListControllers.h> 40 #define SERIOUS_ERROR_FLAGS PALM_0200_EDC_SERIOUS_ERROR_FLAGS 41 #define error_flag_names palm_0200_edc_error_flag_names 46 using std::ostringstream;
47 using sr_actuator::SrMotorActuator;
55 using boost::static_pointer_cast;
60 template<
class StatusType,
class CommandType>
63 string device_id,
string joint_prefix)
64 :
SrRobotLib<StatusType, CommandType>(hw, nh, nhtilde, device_id, joint_prefix),
67 control_type_changed_flag_(false),
68 change_control_type_(this->nh_tilde.advertiseService(
"change_control_type",
71 motor_system_control_server_(
72 this->nh_tilde.advertiseService(
"change_motor_system_controls",
75 lock_command_sending_(new
boost::mutex())
79 string default_control_mode;
80 this->
nh_tilde.template param<string>(
"default_control_mode", default_control_mode,
"FORCE");
81 if (default_control_mode.compare(
"PWM") == 0)
88 control_type_.control_type = sr_robot_msgs::ControlType::FORCE;
92 #ifdef DEBUG_PUBLISHER 93 this->debug_motor_indexes_and_data.resize(this->nb_debug_publishers_const);
94 for (
int i = 0; i < this->nb_debug_publishers_const; ++i)
97 ss <<
"srh/debug_" << i;
98 this->debug_publishers.push_back(this->node_handle.template advertise<std_msgs::Int16>(ss.str().c_str(), 100));
103 template<
class StatusType,
class CommandType>
108 if (status_data->idle_time_us < this->main_pic_idle_time_min)
115 double timestamp = 0.0;
116 if (gettimeofday(&tv, NULL))
117 ROS_WARN(
"SrMotorRobotLib: Failed to get system time, timestamp in state will be zero");
120 timestamp =
static_cast<double>(tv.tv_sec) + static_cast<double>(tv.tv_usec) / 1.0e+6;
124 for (vector<Joint>::iterator joint_tmp = this->
joints_vector.begin();
128 if (!joint_tmp->has_actuator)
143 motor_actuator->motor_state_.tactiles_ = this->
tactiles->get_tactile_data();
149 pair<double, double> effort_and_effort_d = joint_tmp->effort_filter.compute(
150 motor_actuator->motor_state_.force_unfiltered_, timestamp);
151 motor_actuator->state_.last_measured_effort_ = effort_and_effort_d.first;
154 bool read_motor_info =
false;
156 if (status_data->which_motors == 0)
159 if (motor_index_full % 2 == 0)
161 read_motor_info =
true;
167 if (motor_index_full % 2 == 1)
169 read_motor_info =
true;
195 template<
class StatusType,
class CommandType>
206 ROS_FATAL(
"Changing control parameters failed. Stopping real time loop to protect the robot.");
239 case sr_robot_msgs::ControlType::FORCE:
242 case sr_robot_msgs::ControlType::PWM:
252 for (vector<Joint>::iterator joint_tmp = this->
joints_vector.begin();
256 if (!joint_tmp->has_actuator)
266 command->motor_data[motor_wrapper->motor_id] = motor_wrapper->actuator->command_.effort_;
271 command->motor_data[motor_wrapper->motor_id] = 0;
274 joint_tmp->actuator_wrapper->actuator->state_.last_commanded_effort_ =
275 joint_tmp->actuator_wrapper->actuator->command_.effort_;
277 #ifdef DEBUG_PUBLISHER 281 int publisher_index = 0;
283 if (this->debug_mutex.try_lock())
285 BOOST_FOREACH(debug_pair, this->debug_motor_indexes_and_data)
287 if (debug_pair != NULL)
291 if (debug_pair->first == actuator_wrapper->
motor_id)
294 if (debug_pair->second == -1)
296 this->msg_debug.data = joint_tmp->actuator_wrapper->
actuator->command_.effort_;
297 this->debug_publishers[publisher_index].publish(this->msg_debug);
304 this->debug_mutex.unlock();
314 vector<sr_robot_msgs::MotorSystemControls> system_controls_to_send;
321 for (vector<sr_robot_msgs::MotorSystemControls>::iterator it = system_controls_to_send.begin();
322 it != system_controls_to_send.end();
325 int16_t combined_flags = 0;
326 if (it->enable_backlash_compensation)
335 if (it->increase_sgl_tracking)
339 if (it->decrease_sgl_tracking)
344 if (it->increase_sgr_tracking)
348 if (it->decrease_sgr_tracking)
353 if (it->initiate_jiggling)
358 if (it->write_config_to_eeprom)
363 command->motor_data[it->motor_id] = combined_flags;
373 for (vector<Joint>::iterator joint_tmp = this->
joints_vector.begin();
377 if (!joint_tmp->has_actuator)
385 if (motor_wrapper->motor_id == motor_id)
387 actuator->motor_state_.can_msgs_transmitted_ = 0;
388 actuator->motor_state_.can_msgs_received_ = 0;
407 to_send.
byte[0] = motor_id - 10;
411 to_send.
byte[0] = motor_id;
414 command->motor_data[motor_id] = to_send.
word;
449 if (i != motor_index)
451 command->motor_data[i] = 0;
470 template<
class StatusType,
class CommandType>
474 for (vector<Joint>::iterator joint = this->
joints_vector.begin();
478 ostringstream name(
"");
480 name << prefix <<
"SRDMotor " << joint->joint_name;
483 if (joint->has_actuator)
488 if (actuator_wrapper->actuator_ok)
490 if (actuator_wrapper->bad_data)
492 d.
summary(d.WARN,
"WARNING, bad CAN data received");
495 d.
addf(
"Motor ID",
"%d", actuator_wrapper->motor_id);
502 d.
addf(
"Motor ID",
"%d", actuator_wrapper->motor_id);
503 d.
addf(
"Motor ID in message",
"%d", actuator_wrapper->msg_motor_id);
504 d.
addf(
"Serial Number",
"%d", actuator->motor_state_.serial_number);
505 d.
addf(
"Assembly date",
"%d / %d / %d",
506 actuator->motor_state_.assembly_data_day,
507 actuator->motor_state_.assembly_data_month,
508 actuator->motor_state_.assembly_data_year);
510 d.
addf(
"Strain Gauge Left",
"%d", actuator->motor_state_.strain_gauge_left_);
511 d.
addf(
"Strain Gauge Right",
"%d", actuator->motor_state_.strain_gauge_right_);
515 if (actuator->motor_state_.flags_.size() > 0)
517 int flags_seriousness = d.OK;
518 pair<string, bool> flag;
520 BOOST_FOREACH(flag, actuator->motor_state_.flags_)
525 flags_seriousness = d.ERROR;
528 if (flags_seriousness != d.ERROR)
530 flags_seriousness = d.WARN;
532 ss << flag.first <<
" | ";
534 d.
summary(flags_seriousness, ss.str().c_str());
540 d.
addf(
"Motor Flags",
"%s", ss.str().c_str());
542 d.
addf(
"Measured PWM",
"%d", actuator->motor_state_.pwm_);
543 d.
addf(
"Measured Current",
"%f", actuator->state_.last_measured_current_);
544 d.
addf(
"Measured Voltage",
"%f", actuator->state_.motor_voltage_);
545 d.
addf(
"Measured Effort",
"%f", actuator->state_.last_measured_effort_);
546 d.
addf(
"Temperature",
"%f", actuator->motor_state_.temperature_);
548 d.
addf(
"Unfiltered position",
"%f", actuator->motor_state_.position_unfiltered_);
549 d.
addf(
"Unfiltered force",
"%f", actuator->motor_state_.force_unfiltered_);
551 d.
addf(
"Gear Ratio",
"%d", actuator->motor_state_.motor_gear_ratio);
553 d.
addf(
"Number of CAN messages received",
"%lld", actuator->motor_state_.can_msgs_received_);
554 d.
addf(
"Number of CAN messages transmitted",
"%lld", actuator->motor_state_.can_msgs_transmitted_);
556 d.
addf(
"Force control Pterm",
"%d", actuator->motor_state_.force_control_pterm);
557 d.
addf(
"Force control Iterm",
"%d", actuator->motor_state_.force_control_iterm);
558 d.
addf(
"Force control Dterm",
"%d", actuator->motor_state_.force_control_dterm);
560 d.
addf(
"Force control F",
"%d", actuator->motor_state_.force_control_f_);
561 d.
addf(
"Force control P",
"%d", actuator->motor_state_.force_control_p_);
562 d.
addf(
"Force control I",
"%d", actuator->motor_state_.force_control_i_);
563 d.
addf(
"Force control D",
"%d", actuator->motor_state_.force_control_d_);
564 d.
addf(
"Force control Imax",
"%d", actuator->motor_state_.force_control_imax_);
565 d.
addf(
"Force control Deadband",
"%d", actuator->motor_state_.force_control_deadband_);
566 d.
addf(
"Force control Frequency",
"%d", actuator->motor_state_.force_control_frequency_);
568 if (actuator->motor_state_.force_control_sign_ == 0)
570 d.
addf(
"Force control Sign",
"+");
574 d.
addf(
"Force control Sign",
"-");
577 d.
addf(
"Last Commanded Effort",
"%f", actuator->state_.last_commanded_effort_);
579 d.
addf(
"Encoder Position",
"%f", actuator->state_.position_);
581 if (actuator->motor_state_.firmware_modified_)
583 d.
addf(
"Firmware git revision (server / pic / modified)",
"%d / %d / True",
584 actuator->motor_state_.server_firmware_git_revision_,
585 actuator->motor_state_.pic_firmware_git_revision_);
589 d.
addf(
"Firmware git revision (server / pic / modified)",
"%d / %d / False",
590 actuator->motor_state_.server_firmware_git_revision_,
591 actuator->motor_state_.pic_firmware_git_revision_);
597 d.
summary(d.ERROR,
"Motor error");
599 d.
addf(
"Motor ID",
"%d", actuator_wrapper->motor_id);
604 d.
summary(d.OK,
"No motor associated to this joint");
611 template<
class StatusType,
class CommandType>
613 StatusType *status_data)
615 if (!joint_tmp->has_actuator)
622 joint_tmp->actuator_wrapper->actuator_ok = sr_math_utils::is_bit_mask_index_true(
623 status_data->which_motor_data_arrived,
628 joint_tmp->actuator_wrapper->bad_data = sr_math_utils::is_bit_mask_index_true(
629 status_data->which_motor_data_had_errors,
634 if (joint_tmp->actuator_wrapper->actuator_ok && !(joint_tmp->actuator_wrapper->bad_data))
636 SrMotorActuator *actuator =
static_cast<SrMotorActuator *
> (joint_tmp->actuator_wrapper->actuator);
639 #ifdef DEBUG_PUBLISHER 640 int publisher_index = 0;
646 if (this->debug_mutex.try_lock())
648 BOOST_FOREACH(debug_pair, this->debug_motor_indexes_and_data)
650 if (debug_pair != NULL)
655 if (debug_pair->first == actuator_wrapper->
motor_id)
658 if (debug_pair->second > 0)
661 if (debug_pair->second == status_data->motor_data_type)
664 this->debug_publishers[publisher_index].publish(this->msg_debug);
672 this->debug_mutex.unlock();
677 bool read_torque =
true;
678 switch (status_data->motor_data_type)
681 actuator->motor_state_.strain_gauge_left_ =
684 #ifdef DEBUG_PUBLISHER 685 if (actuator_wrapper->
motor_id == 19)
688 this->msg_debug.data = actuator->motor_state_.strain_gauge_left_;
689 this->debug_publishers[0].publish(this->msg_debug);
694 actuator->motor_state_.strain_gauge_right_ =
697 #ifdef DEBUG_PUBLISHER 698 if (actuator_wrapper->
motor_id == 19)
701 this->msg_debug.data = actuator->motor_state_.strain_gauge_right_;
702 this->debug_publishers[1].publish(this->msg_debug);
707 actuator->motor_state_.pwm_ =
710 #ifdef DEBUG_PUBLISHER 711 if (actuator_wrapper->
motor_id == 19)
714 this->msg_debug.data = actuator->motor_state_.pwm_;
715 this->debug_publishers[2].publish(this->msg_debug);
724 actuator->state_.last_measured_current_ =
728 #ifdef DEBUG_PUBLISHER 729 if (actuator_wrapper->
motor_id == 19)
733 this->debug_publishers[3].publish(this->msg_debug);
738 actuator->state_.motor_voltage_ =
742 #ifdef DEBUG_PUBLISHER 743 if (actuator_wrapper->
motor_id == 19)
747 this->debug_publishers[4].publish(this->msg_debug);
752 actuator->motor_state_.temperature_ =
759 actuator->motor_state_.can_msgs_received_ = sr_math_utils::counter_with_overflow(
760 actuator->motor_state_.can_msgs_received_,
766 actuator->motor_state_.can_msgs_transmitted_ = sr_math_utils::counter_with_overflow(
767 actuator->motor_state_.can_msgs_transmitted_,
778 switch (static_cast<int16u> (status_data->motor_data_packet[
index_motor_in_msg].torque))
781 actuator->motor_state_.pic_firmware_git_revision_ =
782 static_cast<unsigned int> (
786 actuator->motor_state_.server_firmware_git_revision_ =
787 static_cast<unsigned int> (
791 actuator->motor_state_.firmware_modified_ =
796 actuator->motor_state_.set_serial_number_low(
797 static_cast<unsigned int> (
801 actuator->motor_state_.set_serial_number_high(
802 static_cast<unsigned int> (
806 actuator->motor_state_.motor_gear_ratio =
807 static_cast<unsigned int> (
811 actuator->motor_state_.assembly_data_year =
812 static_cast<unsigned int> (
816 actuator->motor_state_.assembly_data_month =
817 static_cast<unsigned int> (
820 actuator->motor_state_.assembly_data_day =
821 static_cast<unsigned int> (
826 actuator->motor_state_.force_control_f_ =
827 static_cast<unsigned int> (
831 actuator->motor_state_.force_control_p_ =
832 static_cast<unsigned int> (
836 actuator->motor_state_.force_control_i_ =
837 static_cast<unsigned int> (
841 actuator->motor_state_.force_control_d_ =
842 static_cast<unsigned int> (
846 actuator->motor_state_.force_control_imax_ =
847 static_cast<unsigned int> (
852 actuator->motor_state_.force_control_deadband_ =
static_cast<int> (tmp_value.
byte[0]);
853 actuator->motor_state_.force_control_sign_ =
static_cast<int> (tmp_value.
byte[1]);
856 actuator->motor_state_.force_control_frequency_ =
857 static_cast<unsigned int> (
867 actuator->motor_state_.can_error_counters =
871 actuator->motor_state_.force_control_pterm =
875 actuator->motor_state_.force_control_iterm =
879 actuator->motor_state_.force_control_dterm =
889 actuator->motor_state_.force_unfiltered_ =
892 #ifdef DEBUG_PUBLISHER 893 if (actuator_wrapper->
motor_id == 19)
896 this->debug_publishers[5].publish(this->msg_debug);
905 joint_tmp, status_data->motor_data_type,
911 ROS_INFO(
"All motors were initialized.");
917 template<
class StatusType,
class CommandType>
919 StatusType *status_data)
923 actuator->motor_state_.raw_sensor_values_.clear();
924 actuator->motor_state_.calibrated_sensor_values_.clear();
926 if (joint_tmp->joint_to_sensor.calibrate_after_combining_sensors)
931 double raw_position = 0.0;
935 BOOST_FOREACH(
PartialJointToSensor joint_to_sensor, joint_tmp->joint_to_sensor.joint_to_sensor_vector)
937 int tmp_raw = status_data->sensors[joint_to_sensor.
sensor_id];
938 actuator->motor_state_.raw_sensor_values_.push_back(tmp_raw);
939 raw_position +=
static_cast<double> (tmp_raw) * joint_to_sensor.
coeff;
944 actuator->motor_state_.position_unfiltered_ = this->
calibration_tmp->compute(static_cast<double> (raw_position));
950 double calibrated_position = 0.0;
956 for (
unsigned int index_joint_to_sensor = 0;
957 index_joint_to_sensor < joint_tmp->joint_to_sensor.joint_to_sensor_vector.size();
958 ++index_joint_to_sensor)
960 joint_to_sensor = joint_tmp->joint_to_sensor.joint_to_sensor_vector[index_joint_to_sensor];
961 sensor_name = joint_tmp->joint_to_sensor.sensor_names[index_joint_to_sensor];
964 int raw_pos = status_data->sensors[joint_to_sensor.
sensor_id];
966 actuator->motor_state_.raw_sensor_values_.push_back(raw_pos);
968 double tmp_cal_value;
978 int raw_pos_2nd_joint =
979 status_data->sensors[
981 current_joint->
sibling_name_)].joint_to_sensor.joint_to_sensor_vector[0].sensor_id];
982 xyi[0] =
static_cast<double>(raw_pos);
983 xyi[1] =
static_cast<double>(raw_pos_2nd_joint);
988 tmp_cal_value = zi[0];
993 tmp_cal_value = this->
calibration_tmp->compute(static_cast<double> (raw_pos));
996 actuator->motor_state_.calibrated_sensor_values_.push_back(tmp_cal_value);
998 calibrated_position += tmp_cal_value * joint_to_sensor.
coeff;
1000 ROS_DEBUG_STREAM(
" -> " << sensor_name <<
" raw = " << raw_pos <<
" calibrated = " << calibrated_position);
1002 actuator->motor_state_.position_unfiltered_ = calibrated_position;
1007 template<
class StatusType,
class CommandType>
1017 template<
class StatusType,
class CommandType>
1019 StatusType *status_data,
double timestamp)
1027 pair<double, double> pos_and_velocity = joint_tmp->pos_filter.compute(actuator->motor_state_.position_unfiltered_,
1030 actuator->state_.position_ = pos_and_velocity.first;
1032 actuator->state_.velocity_ = pos_and_velocity.second;
1035 template<
class StatusType,
class CommandType>
1038 vector<pair<string, bool> > flags;
1041 for (
unsigned int i = 0; i < 16; ++i)
1043 pair<string, bool> new_flag;
1045 if (sr_math_utils::is_bit_mask_index_true(flag, i))
1049 new_flag.second =
true;
1053 new_flag.second =
false;
1057 flags.push_back(new_flag);
1063 template<
class StatusType,
class CommandType>
1065 int motor_index,
int max_pwm,
int sg_left,
int sg_right,
int f,
int p,
int i,
int d,
1066 int imax,
int deadband,
int sign,
int torque_limit,
int torque_limiter_gain)
1069 ": max_pwm=" << max_pwm <<
1070 " sgleftref=" << sg_left <<
1071 " sgrightref=" << sg_right <<
1077 " deadband=" << deadband <<
1079 " torque_limit=" << torque_limit <<
1080 " torque_limiter_gain=" << torque_limiter_gain);
1088 value.
word = max_pwm;
1091 value.
byte[0] = sg_left;
1092 value.
byte[1] = sg_right;
1110 value.
byte[0] = deadband;
1111 value.
byte[1] = sign;
1113 ROS_DEBUG_STREAM(
"deadband: " << static_cast<int> (static_cast<int8u> (value.
byte[0])) <<
" value: " <<
1114 static_cast<int16u> (value.
word));
1116 value.
word = torque_limit;
1119 value.
word = torque_limiter_gain;
1127 crc_byte = full_config.at(i).byte[0];
1130 crc_byte = full_config.at(i).byte[1];
1145 config.first = motor_index;
1146 config.second = full_config;
1151 template<
class StatusType,
class CommandType>
1164 template<
class StatusType,
class CommandType>
1166 sr_robot_msgs::ChangeControlType::Request &request,
1167 sr_robot_msgs::ChangeControlType::Response &response)
1170 if (request.control_type.control_type == sr_robot_msgs::ControlType::QUERY)
1177 if ((request.control_type.control_type != sr_robot_msgs::ControlType::PWM) &&
1178 (request.control_type.control_type != sr_robot_msgs::ControlType::FORCE))
1180 string ctrl_type_text =
"";
1181 if (
control_type_.control_type == sr_robot_msgs::ControlType::FORCE)
1183 ctrl_type_text =
"FORCE";
1187 ctrl_type_text =
"PWM";
1190 ROS_ERROR_STREAM(
" The value you specified for the control type (" << request.control_type
1191 <<
") is incorrect. Using " << ctrl_type_text <<
" control.");
1197 if (
control_type_.control_type != request.control_type.control_type)
1219 template<
class StatusType,
class CommandType>
1222 bool success =
true;
1223 string env_variable;
1226 if (control_type == sr_robot_msgs::ControlType::PWM)
1228 env_variable =
"PWM_CONTROL=1";
1229 param_value =
"PWM";
1233 env_variable =
"PWM_CONTROL=0";
1234 param_value =
"FORCE";
1237 string arguments =
"";
1242 string hand_id =
"";
1243 this->
nodehandle_.template param<string>(
"hand_id", hand_id,
"");
1244 ROS_DEBUG(
"hand_id: %s", hand_id.c_str());
1245 arguments +=
" hand_id:=" + hand_id;
1246 ROS_INFO(
"arguments: %s", arguments.c_str());
1248 int result = system((env_variable +
" roslaunch sr_ethercat_hand_config sr_edc_default_controllers.launch" +
1249 arguments).c_str());
1253 ROS_WARN(
"New parameters loaded successfully on Parameter Server");
1260 ros::ServiceClient list_ctrl_client = nh.template serviceClient<controller_manager_msgs::ListControllers>(
1261 "controller_manager/list_controllers");
1262 controller_manager_msgs::ListControllers controllers_list;
1264 if (list_ctrl_client.
call(controllers_list))
1266 for (
unsigned int i = 0; i < controllers_list.response.controller.size(); ++i)
1268 if (
ros::service::exists(controllers_list.response.controller[i].name +
"/reset_gains",
false))
1271 controllers_list.response.controller[i].name +
"/reset_gains");
1272 std_srvs::Empty empty_message;
1273 if (!reset_gains_client.
call(empty_message))
1276 "Failed to reset gains for controller: " << controllers_list.response.controller[i].name);
1295 template<
class StatusType,
class CommandType>
1297 sr_robot_msgs::ChangeMotorSystemControls::Request &request,
1298 sr_robot_msgs::ChangeMotorSystemControls::Response &response)
1300 vector<sr_robot_msgs::MotorSystemControls> tmp_motor_controls;
1302 response.result = sr_robot_msgs::ChangeMotorSystemControls::Response::SUCCESS;
1303 bool no_motor_id_out_of_range =
true;
1305 for (
unsigned int i = 0; i < request.motor_system_controls.size(); ++i)
1307 if (request.motor_system_controls[i].motor_id >=
NUM_MOTORS ||
1308 request.motor_system_controls[i].motor_id < 0)
1310 response.result = sr_robot_msgs::ChangeMotorSystemControls::Response::MOTOR_ID_OUT_OF_RANGE;
1311 no_motor_id_out_of_range =
false;
1316 tmp_motor_controls.push_back(request.motor_system_controls[i]);
1321 if (tmp_motor_controls.size() > 0)
1326 return no_motor_id_out_of_range;
1329 template<
class StatusType,
class CommandType>
1333 for (vector<Joint>::iterator joint = this->
joints_vector.begin();
1337 if (joint->joint_name.find(joint_name) != std::string::npos)
1343 ROS_ERROR(
"Could not find joint with name: %s", joint_name.c_str());
std::vector< int > element_neighbor_
MOTOR_SLOW_DATA_CONTROLLER_P
MOTOR_SLOW_DATA_CONTROLLER_FREQUENCY
void reinitialize_motors()
#define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_DEC
MOTOR_SLOW_DATA_CONTROLLER_D
void generate_force_control_config(int motor_index, int max_pwm, int sg_left, int sg_right, int f, int p, int i, int d, int imax, int deadband, int sign, int torque_limit, int torque_limiter_gain)
MOTOR_SLOW_DATA_CONTROLLER_I
std::vector< shadow_joints::Joint > joints_vector
The vector containing all the robot joints.
MOTOR_SLOW_DATA_CONTROLLER_F
std::pair< int, std::vector< crc_unions::union16 > > ForceConfig
void summary(unsigned char lvl, const std::string s)
#define SERIOUS_ERROR_FLAGS
MOTOR_SLOW_DATA_CONTROLLER_DEADSIGN
#define MOTOR_SYSTEM_CONTROL_INITIATE_JIGGLING
bool call(MReq &req, MRes &res)
ros::NodeHandle nodehandle_
a ros nodehandle to be able to access resources out of the node namespace
MOTOR_SLOW_DATA_SVN_REVISION
#define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_DEC
MOTOR_CONFIG_TORQUE_LIMIT
SrMotorRobotLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
void read_additional_data(std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data)
void build_tactile_command(CommandType *command)
shadow_joints::CalibrationMap calibration_map
The map used to calibrate each joint.
MOTOR_DATA_CAN_NUM_RECEIVED
void addf(const std::string &key, const char *format,...)
ros_ethercat_model::Actuator * actuator
sr_robot_msgs::ControlType control_type_
MOTOR_SLOW_DATA_ASSEMBLY_DATE_YYYY
MOTOR_SLOW_DATA_CONTROLLER_IMAX
std::vector< generic_updater::UpdateConfig > motor_update_rate_configs_vector
#define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_ENABLE
#define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_INC
CoupledJointMapType coupled_calibration_map
boost::shared_ptr< shadow_robot::JointCalibration > calibration_tmp
A temporary calibration for a given joint.
MOTOR_SLOW_DATA_ASSEMBLY_DATE_MMDD
#define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_DISABLE
boost::shared_ptr< generic_updater::MotorUpdater< CommandType > > motor_updater_
ros::NodeHandle nh_tilde
a ROS nodehandle (private naming, only inside the node namespace) to be able to advertise the Force P...
std::queue< int16_t, std::list< int16_t > > reset_motors_queue
MOTOR_CONFIG_DEADBAND_SIGN
boost::shared_ptr< generic_updater::MotorDataChecker > motor_data_checker
sr_actuator::SrMotorActuator * get_joint_actuator(std::vector< shadow_joints::Joint >::iterator joint_tmp)
MOTOR_DATA_CAN_ERROR_COUNTERS
MOTOR_SLOW_DATA_SVN_MODIFIED
MOTOR_SLOW_DATA_SERIAL_NUMBER_HIGH
MOTOR_DATA_CAN_NUM_TRANSMITTED
#define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_INC
#define ROS_DEBUG_STREAM(args)
MOTOR_SLOW_DATA_SERIAL_NUMBER_LOW
#define INSERT_CRC_CALCULATION_HERE
bool control_type_changed_flag_
bool motor_system_controls_callback_(sr_robot_msgs::ChangeMotorSystemControls::Request &request, sr_robot_msgs::ChangeMotorSystemControls::Response &response)
bool change_control_parameters(int16_t control_type)
bool check_if_joint_coupled(string joint_name)
boost::shared_ptr< boost::mutex > lock_command_sending_
MOTOR_CONFIG_TORQUE_LIMITER_GAIN
#define MOTOR_SYSTEM_RESET_KEY
std::vector< double > calibrated_values_
#define ROS_INFO_STREAM(args)
bool change_control_type_callback_(sr_robot_msgs::ChangeControlType::Request &request, sr_robot_msgs::ChangeControlType::Response &response)
void build_command(CommandType *command)
void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
void calibrate_joint(std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data)
operation_mode::device_update_state::DeviceUpdateState motor_current_state
std::string device_id_
Id of the ethercat device (alias)
void update_tactile_info(StatusType *status)
void update(StatusType *status_data)
MOTOR_SLOW_DATA_GEAR_RATIO
std::queue< std::vector< sr_robot_msgs::MotorSystemControls >, std::list< std::vector< sr_robot_msgs::MotorSystemControls > > > motor_system_control_flags_
std::string sibling_name_
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
#define ROS_ERROR_STREAM(args)
#define MOTOR_SYSTEM_CONTROL_EEPROM_WRITE
int find_joint_by_name(string joint_name)
void process_position_sensor_data(std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data, double timestamp)
std::vector< int > triangle_
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
std::vector< double > raw_values_coupled_
std::vector< std::pair< std::string, bool > > humanize_flags(int flag)
int main_pic_idle_time_min
std::queue< ForceConfig, std::list< ForceConfig > > reconfig_queue
MOTOR_SLOW_DATA_SVN_SERVER_REVISION