00001
00026 #include "motor_controller_node.h"
00027
00029
00030 MotorControllerNode::MotorControllerNode(MotorDriverInterface *driver) :
00031 _nh_private("~"),
00032 _publish_rate(10),
00033 _driver(driver)
00034 {
00035
00036
00037 std::string searched_param;
00038 std::string port;
00039
00040
00041 _nh_private.searchParam("port", searched_param);
00042 _nh_private.param(searched_param, port, std::string());
00043
00044
00045 _nh_private.searchParam("joint_name", searched_param);
00046 _nh_private.param(searched_param, _joint_name, std::string());
00047
00048
00049 _nh_private.searchParam("joint_id", searched_param);
00050 _nh_private.param(searched_param, _joint_id, -1);
00051
00052
00053 _serial_device = "/dev/" + port;
00054
00055
00056
00057 int error = -1;
00058 std::string sem_file("/");
00059
00060 if (_joint_name == NECK) {
00061
00062 switch(_joint_id) {
00063 case NECK_HOR:
00064 sem_file += HOR_NECK_SEMAPHORE_FILE;
00065
00066 _pos_factor = TOTAL_NECK_HOR_REDUCTION;
00067 _vel_factor = NECK_HOR_REDUCTION_FACTOR;
00068 _calibration_home = NECK_HOR_HOME_POS;
00069
00070 ROS_INFO("[MOTOR_CONTROLLER] Neck: Horizontal joint chosen. factor_position = %d\n", _pos_factor);
00071 break;
00072
00073 case NECK_VER:
00074 sem_file += VER_NECK_SEMAPHORE_FILE;
00075
00076 _pos_factor = TOTAL_NECK_VER_REDUCTION;
00077 _vel_factor = NECK_VER_REDUCTION_FACTOR;
00078 _calibration_home = NECK_VER_HOME_POS;
00079
00080 ROS_INFO("[MOTOR_CONTROLLER] Neck: Vertical joint chosen. factor_position = %d\n", _pos_factor);
00081 break;
00082
00083 default:
00084 ROS_WARN("[MOTOR_CONTROLLER] You must select the axis of the neck.\n");
00085 exit(EXIT_FAILURE);
00086 }
00087 }
00088 else if (_joint_name == ARM) {
00089
00090 switch(_joint_id) {
00091 case ARM_LEFT:
00092 sem_file += LEFT_ARM_SEMAPHORE_FILE;
00093
00094 ROS_INFO("[MOTOR_CONTROLLER] Arm: left joint chosen");
00095 break;
00096
00097 case ARM_RIGHT:
00098 sem_file += RIGHT_ARM_SEMAPHORE_FILE;
00099
00100 ROS_INFO("[MOTOR_CONTROLLER] Arm: right joint chosen");
00101 break;
00102
00103 default:
00104 ROS_WARN("[MOTOR_CONTROLLER] You must select the correct arm id.\n");
00105 exit(EXIT_FAILURE);
00106 }
00107 }
00108 else {
00109 ROS_ERROR("[MOTOR_CONTROLLER] Error: no correct joint name param specified. Get: '%s', Expected: '%s' or '%s'", _joint_name.c_str(), NECK, ARM);
00110 exit(-1);
00111 }
00112
00113
00114 std::vector<char> wr_serial_device(_serial_device.begin(), _serial_device.end());
00115 wr_serial_device.push_back('\0');
00116 std::vector<char> wr_sem_file(sem_file.begin(), sem_file.end());
00117 wr_sem_file.push_back('\0');
00118
00119
00120 if ((error = _driver->init(BAUDRATE, &wr_serial_device[0], &wr_sem_file[0])) != 0) {
00121 exit(error);
00122 }
00123 }
00124
00126
00127 MotorControllerNode::~MotorControllerNode()
00128 {
00129 _driver->disable_driver();
00130 }
00131
00133
00134 void MotorControllerNode::init()
00135 {
00136 _data_msg = _nh_private.advertise<maggie_motor_controller_msgs::Data>("data_pub", 100);
00137 _odo_msg = _nh_private.advertise<maggie_motor_controller_msgs::Odometry>("odo_pub", 100);
00138
00139 _max_pos_srv = _nh_private.advertiseService("set_max_pos", &MotorControllerNode::set_max_pos, this);
00140 _min_pos_srv = _nh_private.advertiseService("set_min_pos", &MotorControllerNode::set_min_pos, this);
00141 _max_vel_srv = _nh_private.advertiseService("set_max_vel", &MotorControllerNode::set_max_vel, this);
00142 _max_acc_srv = _nh_private.advertiseService("set_max_acc", &MotorControllerNode::set_max_acc, this);
00143 _max_dec_srv = _nh_private.advertiseService("set_max_dec", &MotorControllerNode::set_max_dec, this);
00144 _cur_lim_srv = _nh_private.advertiseService("set_cur_lim", &MotorControllerNode::set_cur_lim, this);
00145
00146 _mov_abs_pos_srv = _nh_private.advertiseService("mov_abs_pos", &MotorControllerNode::move_abs_pos, this);
00147 _mov_rel_pos_srv = _nh_private.advertiseService("mov_rel_pos", &MotorControllerNode::move_rel_pos, this);
00148 _mov_vel_srv = _nh_private.advertiseService("mov_vel", &MotorControllerNode::move_vel, this);
00149
00150 _calibration_srv = _nh_private.advertiseService("joint_calibration", &MotorControllerNode::joint_calibration, this);
00151
00152
00153 _driver->enable_driver();
00154 }
00155
00157
00158 void MotorControllerNode::spin()
00159 {
00160 while(_nh.ok()) {
00161 ros::spinOnce();
00162 _publish_rate.sleep();
00163
00164
00165 publish();
00166 }
00167 }
00168
00170
00171 void MotorControllerNode::publish()
00172 {
00173 maggie_motor_controller_msgs::Data msg_data;
00174 maggie_motor_controller_msgs::Odometry msg_odo;
00175 double factor;
00176 double joint_factor;
00177
00178
00179
00180
00181 joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00182 factor = (2. * M_PI) / joint_factor;
00183
00184
00185 msg_data.max_pos = _driver->get_max_pos() * factor;
00186 msg_data.min_pos = _driver->get_min_pos() * factor;
00187
00188 if (_joint_name == NECK) {
00189 factor = (2. * M_PI) / _vel_factor / 60.;
00190 }
00191 else {
00192 factor = (2. * M_PI) * PULSES_PER_REV / ARMS_REDUCTION_FACTOR / 60. / 60.;
00193 }
00194
00195
00196 msg_data.max_vel = _driver->get_max_vel() * factor;
00197 msg_data.max_acc = _driver->get_max_acc() * factor;
00198 msg_data.max_dec = _driver->get_max_dec() * factor;
00199 msg_data.max_cur_lim = _driver->get_cur_lim();
00200
00201
00202 _data_msg.publish(msg_data);
00203
00204
00205
00206 double pos_factor, vel_factor;
00207 driverSensor_t dOdo;
00208
00209
00210 joint_factor = (_joint_name == NECK ? _pos_factor : ARMS_REDUCTION_FACTOR);
00211 pos_factor = (2. * M_PI) / joint_factor;
00212
00213 joint_factor = (_joint_name == NECK ? _vel_factor : (PULSES_PER_REV / ARMS_REDUCTION_FACTOR));
00214 vel_factor = (2. * M_PI) / joint_factor / 60.;
00215
00216
00217 _driver->get_sensor(&dOdo);
00218
00219
00220 msg_odo.position = dOdo.p * pos_factor;
00221 msg_odo.velocity = dOdo.v * vel_factor;
00222 msg_odo.current = dOdo.i;
00223
00224
00225 _odo_msg.publish(msg_odo);
00226 }
00227
00229
00230 bool MotorControllerNode::set_max_pos(maggie_motor_controller_msgs::Configuration::Request & req,
00231 maggie_motor_controller_msgs::Configuration::Response & resp)
00232 {
00233
00234 double joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00235 double factor = joint_factor / (2. * M_PI);
00236
00237 _driver->set_max_pos(req.max_pos * factor);
00238
00239 return true;
00240 }
00241
00243
00244 bool MotorControllerNode::set_min_pos(maggie_motor_controller_msgs::Configuration::Request & req,
00245 maggie_motor_controller_msgs::Configuration::Response & resp)
00246 {
00247 double joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00248 double factor = joint_factor / (2. * M_PI);
00249
00250 _driver->set_min_pos(req.min_pos * factor);
00251
00252 return true;
00253 }
00254
00256
00257 bool MotorControllerNode::set_max_vel(maggie_motor_controller_msgs::Configuration::Request & req,
00258 maggie_motor_controller_msgs::Configuration::Response & resp)
00259 {
00260 double joint_factor = (_joint_name == NECK ? _vel_factor : TOTAL_ARMS_REDUCTION);
00261 double factor = joint_factor * 60. / (2. * M_PI);
00262
00263 _driver->set_max_vel(req.max_vel * factor);
00264
00265 return true;
00266 }
00267
00269
00270 bool MotorControllerNode::set_max_acc(maggie_motor_controller_msgs::Configuration::Request & req,
00271 maggie_motor_controller_msgs::Configuration::Response & resp)
00272 {
00273 double joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00274 double factor = joint_factor / (2. * M_PI);
00275
00276 _driver->set_max_acc(req.max_acc * factor);
00277
00278 return true;
00279 }
00280
00282
00283 bool MotorControllerNode::set_max_dec(maggie_motor_controller_msgs::Configuration::Request & req,
00284 maggie_motor_controller_msgs::Configuration::Response & resp)
00285 {
00286 double joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00287 double factor = joint_factor / (2. * M_PI);
00288
00289 _driver->set_max_dec(req.max_dec * factor);
00290
00291 return true;
00292 }
00293
00295
00296 bool MotorControllerNode::set_cur_lim(maggie_motor_controller_msgs::Configuration::Request & req,
00297 maggie_motor_controller_msgs::Configuration::Response & resp)
00298 {
00299 _driver->set_cur_lim(req.cur);
00300
00301 return true;
00302 }
00303
00305
00307
00308 bool MotorControllerNode::move_abs_pos(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00309 maggie_motor_controller_msgs::MoveAbsPos::Response & resp)
00310 {
00311 ROS_DEBUG("[MOTOR_CONTROLLER] moveAbsPos pos = %f\n", req.position);
00312
00313 long int joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00314 long int factor = joint_factor / (2. * M_PI);
00315
00316 _driver->move_abs_pos(int(req.position * factor));
00317
00318 return true;
00319 }
00320
00322
00323 bool MotorControllerNode::move_rel_pos(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00324 maggie_motor_controller_msgs::MoveAbsPos::Response & resp)
00325 {
00326 ROS_DEBUG("[MOTOR_CONTROLLER] moveRelPos pos = %f\n", req.position);
00327
00328 long int joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00329 long int factor = joint_factor / (2. * M_PI);
00330
00331 _driver->move_rel_pos(int(req.position * factor));
00332
00333 return true;
00334 }
00335
00337
00338 bool MotorControllerNode::move_vel(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00339 maggie_motor_controller_msgs::MoveAbsPos::Response & resp)
00340 {
00341 ROS_DEBUG("[MOTOR_CONTROLLER] moveVel vel = %f\n", req.position);
00342
00343
00344 long int joint_factor = (_joint_name == NECK ? _vel_factor : TOTAL_ARMS_REDUCTION / PULSES_PER_REV);
00345 long int factor = joint_factor * 60. / (2. * M_PI);
00346
00347 _driver->move_vel(int(req.position * factor));
00348
00349 return true;
00350 }
00351
00353
00354 bool MotorControllerNode::joint_calibration(maggie_motor_controller_msgs::MoveAbsPos::Request & req,
00355 maggie_motor_controller_msgs::MoveAbsPos::Response & resp)
00356 {
00357 ROS_DEBUG("[MOTOR_CONTROLLER] joint calibration\n");
00358
00359 long int joint_factor = (_joint_name == NECK ? _pos_factor : TOTAL_ARMS_REDUCTION);
00360 long int factor = joint_factor / (2. * M_PI);
00361
00362 _driver->calibrate(int(_calibration_home * factor));
00363
00364 ROS_INFO("Home in pulses: %d\tFactor: %ld\tHome in radians: %f\t", int(_calibration_home * factor), factor, _calibration_home);
00365
00366 return true;
00367 }
00368
00370