Go to the documentation of this file.00001 
00032 #include "husky_base/husky_hardware.h"
00033 #include <boost/assign/list_of.hpp>
00034 
00035 namespace
00036 {
00037   const uint8_t LEFT = 0, RIGHT = 1;
00038 };
00039 
00040 namespace husky_base
00041 {
00042 
00046   HuskyHardware::HuskyHardware(ros::NodeHandle nh, ros::NodeHandle private_nh, double target_control_freq)
00047     :
00048     nh_(nh),
00049     private_nh_(private_nh),
00050     system_status_task_(husky_status_msg_),
00051     power_status_task_(husky_status_msg_),
00052     safety_status_task_(husky_status_msg_),
00053     software_status_task_(husky_status_msg_, target_control_freq)
00054   {
00055     private_nh_.param<double>("wheel_diameter", wheel_diameter_, 0.3302);
00056     private_nh_.param<double>("max_accel", max_accel_, 5.0);
00057     private_nh_.param<double>("max_speed", max_speed_, 1.0);
00058     private_nh_.param<double>("polling_timeout_", polling_timeout_, 10.0);
00059 
00060     std::string port;
00061     private_nh_.param<std::string>("port", port, "/dev/prolific");
00062 
00063     horizon_legacy::connect(port);
00064     horizon_legacy::configureLimits(max_speed_, max_accel_);
00065     resetTravelOffset();
00066     initializeDiagnostics();
00067     registerControlInterfaces();
00068   }
00069 
00073   void HuskyHardware::resetTravelOffset()
00074   {
00075     horizon_legacy::Channel<clearpath::DataEncoders>::Ptr enc = horizon_legacy::Channel<clearpath::DataEncoders>::requestData(
00076       polling_timeout_);
00077     if (enc)
00078     {
00079       for (int i = 0; i < 4; i++)
00080       {
00081         joints_[i].position_offset = linearToAngular(enc->getTravel(i % 2));
00082       }
00083     }
00084     else
00085     {
00086       ROS_ERROR("Could not get encoder data to calibrate travel offset");
00087     }
00088   }
00089 
00093   void HuskyHardware::initializeDiagnostics()
00094   {
00095     horizon_legacy::Channel<clearpath::DataPlatformInfo>::Ptr info =
00096       horizon_legacy::Channel<clearpath::DataPlatformInfo>::requestData(polling_timeout_);
00097     std::ostringstream hardware_id_stream;
00098     hardware_id_stream << "Husky " << info->getModel() << "-" << info->getSerial();
00099 
00100     diagnostic_updater_.setHardwareID(hardware_id_stream.str());
00101     diagnostic_updater_.add(system_status_task_);
00102     diagnostic_updater_.add(power_status_task_);
00103     diagnostic_updater_.add(safety_status_task_);
00104     diagnostic_updater_.add(software_status_task_);
00105     diagnostic_publisher_ = nh_.advertise<husky_msgs::HuskyStatus>("status", 10);
00106   }
00107 
00108 
00112   void HuskyHardware::registerControlInterfaces()
00113   {
00114     ros::V_string joint_names = boost::assign::list_of("front_left_wheel")
00115       ("front_right_wheel")("rear_left_wheel")("rear_right_wheel");
00116     for (unsigned int i = 0; i < joint_names.size(); i++)
00117     {
00118       hardware_interface::JointStateHandle joint_state_handle(joint_names[i],
00119                                                               &joints_[i].position, &joints_[i].velocity,
00120                                                               &joints_[i].effort);
00121       joint_state_interface_.registerHandle(joint_state_handle);
00122 
00123       hardware_interface::JointHandle joint_handle(
00124         joint_state_handle, &joints_[i].velocity_command);
00125       velocity_joint_interface_.registerHandle(joint_handle);
00126     }
00127     registerInterface(&joint_state_interface_);
00128     registerInterface(&velocity_joint_interface_);
00129   }
00130 
00134   void HuskyHardware::updateDiagnostics()
00135   {
00136     diagnostic_updater_.force_update();
00137     husky_status_msg_.header.stamp = ros::Time::now();
00138     diagnostic_publisher_.publish(husky_status_msg_);
00139   }
00140 
00144   void HuskyHardware::updateJointsFromHardware()
00145   {
00146 
00147     horizon_legacy::Channel<clearpath::DataEncoders>::Ptr enc = horizon_legacy::Channel<clearpath::DataEncoders>::requestData(
00148       polling_timeout_);
00149     if (enc)
00150     {
00151       ROS_DEBUG_STREAM("Received travel information (L:" << enc->getTravel(LEFT) << " R:" << enc->getTravel(RIGHT) << ")");
00152       for (int i = 0; i < 4; i++)
00153       {
00154         double delta = linearToAngular(enc->getTravel(i % 2)) - joints_[i].position - joints_[i].position_offset;
00155 
00156         
00157         if (std::abs(delta) < 1.0)
00158         {
00159           joints_[i].position += delta;
00160         }
00161         else
00162         {
00163           
00164           joints_[i].position_offset += delta;
00165           ROS_DEBUG("Dropping overflow measurement from encoder");
00166         }
00167       }
00168     }
00169 
00170     horizon_legacy::Channel<clearpath::DataDifferentialSpeed>::Ptr speed = horizon_legacy::Channel<clearpath::DataDifferentialSpeed>::requestData(
00171       polling_timeout_);
00172     if (speed)
00173     {
00174       ROS_DEBUG_STREAM("Received linear speed information (L:" << speed->getLeftSpeed() << " R:" << speed->getRightSpeed() << ")");
00175       for (int i = 0; i < 4; i++)
00176       {
00177         if (i % 2 == LEFT)
00178         {
00179           joints_[i].velocity = linearToAngular(speed->getLeftSpeed());
00180         }
00181         else
00182         { 
00183           joints_[i].velocity = linearToAngular(speed->getRightSpeed());
00184         }
00185       }
00186     }
00187   }
00188 
00192   void HuskyHardware::writeCommandsToHardware()
00193   {
00194     double diff_speed_left = angularToLinear(joints_[LEFT].velocity_command);
00195     double diff_speed_right = angularToLinear(joints_[RIGHT].velocity_command);
00196 
00197     limitDifferentialSpeed(diff_speed_left, diff_speed_right);
00198 
00199     horizon_legacy::controlSpeed(diff_speed_left, diff_speed_right, max_accel_, max_accel_);
00200   }
00201 
00205   void HuskyHardware::reportLoopDuration(const ros::Duration &duration)
00206   {
00207     software_status_task_.updateControlFrequency(1 / duration.toSec());
00208   }
00209 
00213   void HuskyHardware::limitDifferentialSpeed(double &diff_speed_left, double &diff_speed_right)
00214   {
00215     double large_speed = std::max(std::abs(diff_speed_left), std::abs(diff_speed_right));
00216 
00217     if (large_speed > max_speed_)
00218     {
00219       diff_speed_left *= max_speed_ / large_speed;
00220       diff_speed_right *= max_speed_ / large_speed;
00221     }
00222   }
00223 
00227   double HuskyHardware::linearToAngular(const double &travel) const
00228   {
00229     return travel / wheel_diameter_ * 2;
00230   }
00231 
00235   double HuskyHardware::angularToLinear(const double &angle) const
00236   {
00237     return angle * wheel_diameter_ / 2;
00238   }
00239 
00240 
00241 }