26 #ifndef SR_JOINT_MOTOR_HPP_ 27 #define SR_JOINT_MOTOR_HPP_ 29 #include <sr_hardware_interface/sr_actuator.hpp> 31 #include <sr_utilities/sr_math_utils.hpp> 32 #include <sr_utilities/calibration.hpp> 33 #include <sr_utilities/thread_safe_map.hpp> 55 int muscle_driver_id[2];
118 : muscle_driver_id(id),
119 can_msgs_received_(0),
120 can_msgs_transmitted_(0),
121 pic_firmware_git_revision_(0),
122 server_firmware_git_revision_(0),
123 firmware_modified_(0),
125 assembly_date_year(0),
126 assembly_date_month(0),
127 assembly_date_day(0),
171 int muscle_driver_id[2];
194 typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> >
CalibrationMap;
unsigned int assembly_date_day
JointToSensor joint_to_sensor
std::vector< std::string > sensor_names
unsigned int assembly_date_year
uint64_t can_msgs_transmitted_
ros::ServiceServer reset_motor_service
ros_ethercat_model::Actuator * actuator
std::vector< PartialJointToSensor > joint_to_sensor_vector
unsigned int pic_firmware_git_revision_
sr_math_utils::filters::LowPassFilter pos_filter
unsigned int assembly_date_month
ros::ServiceServer force_pid_service
boost::shared_ptr< SrActuatorWrapper > actuator_wrapper
ros::ServiceServer reset_driver_service
uint64_t can_msgs_received_
unsigned int serial_number
threadsafe::Map< boost::shared_ptr< shadow_robot::JointCalibration > > CalibrationMap
bool calibrate_after_combining_sensors
sr_math_utils::filters::LowPassFilter effort_filter
unsigned int server_firmware_git_revision_