4 #include <boost/assign/list_of.hpp> 6 #define polling_timeout_ 20 10 const uint8_t LEFT = 0, RIGHT = 1;
18 std::ostringstream ostream;
21 ostream << std::setfill(
'0') << std::uppercase;
22 for (
unsigned int i=0; i < data.
length; i++)
23 ostream << std::hex << std::setw(2) <<
static_cast<unsigned int>(data.
data[i]) <<
" " << std::dec;
25 std_msgs::StringPtr
msg(
new std_msgs::String);
26 msg->data = ostream.str();
27 ROS_INFO(
"reveive command:%s",msg->data.c_str());
35 double acc = (accel_left + accel_right)*0.5;
66 ROS_INFO_STREAM(
"Received Wheel data information, Wheel Gauge: "<<wheelData->getWheelGauge()<<
", Wheel Diameter: "<<wheelData->getWheelDiameter());
70 ROS_ERROR(
"Could not get Wheel Data form MCU.");
78 ROS_DEBUG_STREAM(
"Received speed information (speed:" << overallspeed->getTranslational() <<
" Rotational:" << overallspeed->getRotational()<<
" Acceleration:"<<overallspeed->getTransAccel() <<
")");
80 ROS_INFO(
"Received speed information, speed:%.2lf, Rotational:%.2lf, Acceleration:%.2lf",overallspeed->getTranslational(),overallspeed->getRotational(),overallspeed->getTransAccel());
86 int main(
int argc,
char** argv){
89 std::string port =
"/dev/roch";
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
roch_driver::RawData getdata()
static Transport & instance()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
void controloverallSpeed(double lin_vel, double ang_vel, double accel_left, double accel_right)
void connect(std::string port)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
void speedCallBack(const geometry_msgs::Twist::ConstPtr &speed)
unsigned char data[MAX_MSG_LENGTH]
ros::Subscriber speedSubscriber_
#define ROS_ERROR_STREAM(args)
static Ptr requestData(double timeout)