test_wheelinfo.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include "roch_base/roch_hardware.h"
00003 
00004 #include <boost/assign/list_of.hpp>
00005 #include <float.h>
00006 #define polling_timeout_ 20
00007 using namespace std;
00008 namespace
00009 {
00010   const uint8_t LEFT = 0, RIGHT = 1;
00011 };
00012 
00013 double speed_x;
00014 double speed_z;
00015 void publishRawData()
00016 {
00017 #if 1
00018         std::ostringstream ostream;
00019       sawyer::base_data::RawData data =sawyer::Transport::instance().getdata();
00020       ostream << " { " ;
00021       ostream << std::setfill('0') << std::uppercase;
00022       for (unsigned int i=0; i < data.length; i++)
00023           ostream << std::hex << std::setw(2) << static_cast<unsigned int>(data.data[i]) << " " << std::dec;
00024       ostream << "}";
00025       std_msgs::StringPtr msg(new std_msgs::String);
00026       msg->data = ostream.str();
00027       ROS_INFO("reveive command:%s",msg->data.c_str());
00028 #endif
00029 }
00030 
00031 void controloverallSpeed(double lin_vel, double ang_vel, double accel_left, double accel_right)
00032   {
00033     bool success = false;
00034     
00035     double acc = (accel_left + accel_right)*0.5;
00036     
00037     while (!success)
00038     {
00039       try
00040       {
00041 //      sawyer::SetVelocity(lin_vel,ang_vel,acc).send();
00042     sawyer::SetWheelInfo(lin_vel,ang_vel).send();
00043         success = true;
00044       }
00045       catch (sawyer::Exception *ex)
00046       {
00047         ROS_ERROR_STREAM("Error sending Wheel Info command: " << ex->message);
00048        
00049       }
00050     }
00051   }
00052 void speedCallBack(const geometry_msgs::Twist::ConstPtr& speed){
00053   
00054     //cout<<"setspeed "<<speed_x<<"  "<<speed_z<<endl;
00055   speed_x = speed->linear.x;
00056   speed_z = speed->angular.z;
00057   
00058   
00059     controloverallSpeed(speed_x, speed_z, 0, 0);   
00060       
00061     publishRawData();
00062   core::Channel<sawyer::DataWheelInfo>::Ptr wheelData = core::Channel<sawyer::DataWheelInfo>::requestData(
00063      polling_timeout_);
00064    publishRawData();
00065      if(wheelData){
00066       ROS_INFO_STREAM("Received  Wheel data information, Wheel Gauge: "<<wheelData->getWheelGauge()<<", Wheel Diameter: "<<wheelData->getWheelDiameter());    
00067       
00068     }
00069     else{
00070        ROS_ERROR("Could not get Wheel Data form MCU.");
00071     }
00072 #if 0
00073     core::Channel<sawyer::DataVelocity>::Ptr overallspeed = core::Channel<sawyer::DataVelocity>::requestData(
00074       polling_timeout_);
00075       publishRawData();
00076     if (overallspeed)
00077     {
00078       ROS_DEBUG_STREAM("Received  speed information (speed:" << overallspeed->getTranslational() << " Rotational:" << overallspeed->getRotational()<<" Acceleration:"<<overallspeed->getTransAccel() << ")");
00079 
00080       ROS_INFO("Received  speed information,  speed:%.2lf, Rotational:%.2lf, Acceleration:%.2lf",overallspeed->getTranslational(),overallspeed->getRotational(),overallspeed->getTransAccel());     
00081 
00082     }
00083 #endif
00084 }
00085 ros::Subscriber speedSubscriber_;
00086 int main(int argc, char** argv){
00087   
00088   ros::init(argc,argv,"test_imu");
00089   std::string port = "/dev/roch";
00090   core::connect(port);
00091   
00092   ros::NodeHandle nh;
00093   speedSubscriber_ = nh.subscribe("/twist_mux/keyboard_teleop/cmd_vel",100000,&speedCallBack);
00094 
00095     ROS_INFO("begin send requestData");
00096  
00097    ros::spin();
00098   return 0;
00099 }


roch_base
Author(s): Mike Purvis , Paul Bovbel , Carl
autogenerated on Sat Jun 8 2019 20:32:33