esc_ros.h
Go to the documentation of this file.
00001 /*
00002  * esc_ros.h
00003  *
00004  *  Created on: Jul 26, 2012
00005  *      Author: Berk Calli, Wouter Caarls
00006  *      Organization: Delft Biorobotics Lab., Delft University of Technology
00007  *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
00008  *
00009  *      Header of the ROS wrapper for extremum seeking control nodes.
00010  */
00011 
00012 #ifndef ESC_ROS_H_
00013 #define ESC_ROS_H_
00014 
00015 #include <ros/ros.h>
00016 #include <std_msgs/Float32.h>
00017 #include <std_msgs/Float32MultiArray.h>
00018 #include <std_msgs/Bool.h>
00019 #include <std_msgs/Empty.h>
00020 #include <esc_common/esc.h>
00021 #include <string>
00022 #include <esc_ros/Monitors.h>
00023 #include <esc_ros/StateValue.h>
00024 
00025 class ESCROS{
00026 protected:
00027         ESC* esc_;
00028         ros::Publisher pub_ref_, pub_monitor_, pub_stopped_;
00029         ros::Subscriber sub_obj_val_, sub_enable_;
00030         ros::NodeHandle* n_;
00031         double obj_val_;
00032         std::vector<double> state_vec_;
00033         bool initialized_, monitor_, first_obj_val_received_,enabled_, reference_zeroed_;
00034         double period_;
00035         unsigned int opt_dim_;
00036 
00037 public:
00038         ESCROS(ros::NodeHandle* n=NULL);
00039         virtual void init(ESC* esc);
00040         virtual void step();
00041         virtual void spin();
00042         virtual void reset();
00043         virtual void enableCallback(std_msgs::Bool msg);
00044         virtual ~ESCROS(){};
00045 protected:
00046         virtual void objValCallback(std_msgs::Float32 msg);
00047         virtual void objValWithStateCallback(esc_ros::StateValue msg);
00048 
00049 };
00050 
00051 
00052 
00053 
00054 #endif /* ESC_ROS_H_ */


esc_ros
Author(s): Berk Calli and Wouter Caarls
autogenerated on Sun Jan 5 2014 11:07:02