source: trunk/extremum_seeking/esc_test/src/esc_test.cpp @ 11

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

Updated extremum_seeking to revision 1001

File size: 1.3 KB
Line 
1#include <ros/ros.h>
2#include <std_msgs/Float32.h>
3#include <std_msgs/Float32MultiArray.h>
4#include <esc_ros/StateValue.h>
5#include <esc_test/esc_test.h>
6
7void ESCTest::velocityCallback(const std_msgs::Float32MultiArray::ConstPtr &msg)
8{
9  system_->step(msg->data);
10  publish();
11}
12
13void ESCTest::positionCallback(const std_msgs::Float32MultiArray::ConstPtr &msg)
14{
15  system_->set(msg->data);
16  publish();
17}
18
19void ESCTest::publish()
20{
21  std_msgs::Float32 val;
22  val.data = system_->value();
23  val_pub_.publish(val);
24
25  esc_ros::StateValue state_val;
26  state_val.state = system_->state();
27  state_val.value = system_->value();
28  state_val_pub_.publish(state_val);
29}
30
31void ESCTest::init(ESCSystem *system)
32{
33  ROS_INFO("Initializing ESC test node");
34
35  system_ = system;
36 
37  val_pub_ = nh_.advertise<std_msgs::Float32>("obj_val", 1, true);
38  state_val_pub_ = nh_.advertise<esc_ros::StateValue>("esc_in", 1, true);
39  vel_sub_ = nh_.subscribe("vel_ref", 1, &ESCTest::velocityCallback, this);
40  pos_sub_ = nh_.subscribe("pos_ref", 1, &ESCTest::positionCallback, this);
41
42  publish(); 
43}
44
45void ESCTest::spin()
46{
47  ROS_INFO("Spinning");
48
49  ros::spin();
50}
51
52int main(int argc, char **argv)
53{
54  ros::init(argc, argv, "esc_test");
55 
56  ESCTest test;
57 
58  test.init(new ESCSystem(new Gauss(-1, 2, 1)));
59  test.spin();
60 
61  return 0;
62}
Note: See TracBrowser for help on using the repository browser.