test_imu.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
4 #include <boost/assign/list_of.hpp>
5 #include <float.h>
6 #define polling_timeout_ 20
7 using namespace std;
8 namespace
9 {
10  const uint8_t LEFT = 0, RIGHT = 1;
11 };
12 
13 double speed_x;
14 double speed_z;
16 {
17 #if 0
18  std::ostringstream ostream;
20  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;
24  ostream << "}";
25  std_msgs::StringPtr msg(new std_msgs::String);
26  msg->data = ostream.str();
27  ROS_INFO("reveive command:%s",msg->data.c_str());
28 #endif
29 }
30 
31 void controloverallSpeed(double lin_vel, double ang_vel, double accel_left, double accel_right)
32  {
33  bool success = false;
34 
35  double acc = (accel_left + accel_right)*0.5;
36 
37  while (!success)
38  {
39  try
40  {
41  sawyer::SetVelocity(lin_vel,ang_vel,acc).send();
42  success = true;
43  }
44  catch (sawyer::Exception *ex)
45  {
46  ROS_ERROR_STREAM("Error sending velocity setpt command: " << ex->message);
47 
48  }
49  }
50  }
51 void speedCallBack(const geometry_msgs::Twist::ConstPtr& speed){
52 
53  //cout<<"setspeed "<<speed_x<<" "<<speed_z<<endl;
54  speed_x = speed->linear.x;
55  speed_z = speed->angular.z;
56 
57 
59 
64  if(imuRateData){
65  ROS_DEBUG_STREAM("Received imu rate data information (Angle:" << imuRateData->getAngle() << " Angle rate:" << imuRateData->getAngleRate() << ")");
66  ROS_INFO("Received imu rate data information, angle:%.2lf, Angle rate:%.2lf",imuRateData->getAngle(),imuRateData->getAngleRate());
67 
68  }
69  else{
70  ROS_ERROR("Could not get imu data to calibrate rate offset");
71  }
72 #if 0
76  if (overallspeed)
77  {
78  ROS_DEBUG_STREAM("Received speed information (speed:" << overallspeed->getTranslational() << " Rotational:" << overallspeed->getRotational()<<" Acceleration:"<<overallspeed->getTransAccel() << ")");
79 
80  ROS_INFO("Received speed information, speed:%.2lf, Rotational:%.2lf, Acceleration:%.2lf",overallspeed->getTranslational(),overallspeed->getRotational(),overallspeed->getTransAccel());
81 
82  }
83 #endif
84 }
86 int main(int argc, char** argv){
87 
88  ros::init(argc,argv,"test_imu");
89  std::string port = "/dev/roch";
90  core::connect(port);
91 
92  ros::NodeHandle nh;
93  speedSubscriber_ = nh.subscribe("/twist_mux/keyboard_teleop/cmd_vel",100000,&speedCallBack);
94 
95  ROS_INFO("begin send requestData");
96 
97  ros::spin();
98  return 0;
99 }
msg
int main(int argc, char **argv)
Definition: test_imu.cpp:86
void controloverallSpeed(double lin_vel, double ang_vel, double accel_left, double accel_right)
Definition: test_imu.cpp:31
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber speedSubscriber_
Definition: test_imu.cpp:85
roch_driver::RawData getdata()
Definition: Transport.h:103
double speed_z
Definition: test_imu.cpp:14
static Transport & instance()
Definition: Transport.cpp:129
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
data
double speed_x
Definition: test_imu.cpp:11
ROSCPP_DECL void spin(Spinner &spinner)
const char * message
Definition: Exception.h:49
#define ROS_INFO(...)
void connect(std::string port)
#define ROS_DEBUG_STREAM(args)
void speedCallBack(const geometry_msgs::Twist::ConstPtr &speed)
Definition: test_imu.cpp:51
unsigned char data[MAX_MSG_LENGTH]
Definition: serial.h:62
#define polling_timeout_
Definition: test_imu.cpp:6
void publishRawData()
Definition: test_imu.cpp:15
#define ROS_ERROR_STREAM(args)
static Ptr requestData(double timeout)
Definition: core_wrapper.h:98
#define ROS_ERROR(...)


roch_base
Author(s): Mike Purvis , Paul Bovbel , Chen
autogenerated on Mon Jun 10 2019 14:41:14