esc_test.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <std_msgs/Float32.h>
00003 #include <std_msgs/Float32MultiArray.h>
00004 #include <esc_ros/StateValue.h>
00005 #include <esc_test/esc_test.h>
00006 
00007 void ESCTest::velocityCallback(const std_msgs::Float32MultiArray::ConstPtr &msg)
00008 {
00009   vel_ = msg->data;
00010   pos_.clear();
00011 }
00012 
00013 void ESCTest::positionCallback(const std_msgs::Float32MultiArray::ConstPtr &msg)
00014 {
00015   pos_ = msg->data;
00016   vel_.clear();
00017 }
00018 
00019 void ESCTest::publish()
00020 {
00021   std_msgs::Float32 val;
00022   val.data = system_->value();
00023   val_pub_.publish(val);
00024 
00025   esc_ros::StateValue state_val;
00026   state_val.state = system_->state();
00027   state_val.value = system_->value();
00028   state_val_pub_.publish(state_val);
00029 }
00030 
00031 void ESCTest::init(ESCSystem *system)
00032 {
00033   ROS_INFO("Initializing ESC test node");
00034 
00035   system_ = system;
00036   
00037   val_pub_ = nh_.advertise<std_msgs::Float32>("obj_val", 1, true);
00038   state_val_pub_ = nh_.advertise<esc_ros::StateValue>("esc_in", 1, true);
00039   vel_sub_ = nh_.subscribe("vel_ref", 1, &ESCTest::velocityCallback, this);
00040   pos_sub_ = nh_.subscribe("pos_ref", 1, &ESCTest::positionCallback, this);
00041 }
00042 
00043 void ESCTest::spin()
00044 {
00045   ROS_INFO("Spinning");
00046 
00047   ros::Rate loop_rate(100);
00048   while (nh_.ok())
00049   {
00050     if (!vel_.empty())
00051       system_->step(vel_);
00052     else if (!pos_.empty())
00053       system_->set(pos_);
00054     publish();
00055 
00056     loop_rate.sleep();
00057     ros::spinOnce();
00058   }  
00059 }
00060 
00061 int main(int argc, char **argv)
00062 {
00063   ros::init(argc, argv, "esc_test");
00064   
00065   ESCFunction *function;
00066   
00067   if (argc > 1 && strcmp(argv[1], "-2") == 0)
00068   {
00069     std::vector<float> mean, sigma;
00070     mean.push_back(0.5);
00071     mean.push_back(0.2);
00072     sigma.push_back(0.15);
00073     sigma.push_back(0.15);
00074     function = new Gauss2D(2, -1, mean, sigma);
00075   }
00076   else
00077     function = new Gauss1D(2.5, -1.5, 0.4, 0.27/sqrt(2.0));
00078   
00079   ESCTest test;
00080   
00081   test.init(new ESCSystem(function));
00082   test.spin();
00083   
00084   return 0;
00085 }


esc_test
Author(s): Wouter Caarls
autogenerated on Sun Jan 5 2014 11:07:17