source: trunk/extremum_seeking/esc_ros/include/esc_ros/esc_ros.h @ 5

Last change on this file since 5 was 5, checked in by wcaarls, 12 years ago

Imported extremum_seeking at revision 987

File size: 1.1 KB
Line 
1/*
2 * esc_ros.h
3 *
4 *  Created on: Jul 26, 2012
5 *      Author: Berk Calli, Wouter Caarls
6 *      Organization: Delft Biorobotics Lab., Delft University of Technology
7 *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
8 *
9 *      Header of the ROS wrapper for extremum seeking control nodes.
10 */
11
12#ifndef ESC_ROS_H_
13#define ESC_ROS_H_
14
15#include <ros/ros.h>
16#include <std_msgs/Float32.h>
17#include <std_msgs/Float32MultiArray.h>
18#include <esc_common/esc.h>
19#include <string>
20#include "esc_ros/monitor.h"
21#include "esc_ros/esc_w_state.h"
22class ESCROS{
23protected:
24        ESC* esc_;
25        ros::Publisher pub_ref_, pub_monitor_;
26        ros::Subscriber sub_obj_val_;
27        ros::NodeHandle* n_;
28        double obj_val_;
29        std::vector<double> state_vec_;
30        bool initialized_, monitor_, first_obj_val_received_;
31        double period_;
32
33public:
34        ESCROS(ros::NodeHandle* n=NULL);
35        virtual void init(ESC* esc);
36        virtual void step();
37        virtual void spin();
38        virtual ~ESCROS(){};
39protected:
40        virtual void objValCallback(std_msgs::Float32 msg);
41        virtual void objValWithStateCallback(esc_ros::esc_w_state msg);
42
43};
44
45
46
47
48#endif /* ESC_ROS_H_ */
Note: See TracBrowser for help on using the repository browser.