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 | |
---|
7 | void ESCTest::velocityCallback(const std_msgs::Float32MultiArray::ConstPtr &msg) |
---|
8 | { |
---|
9 | vel_ = msg->data; |
---|
10 | pos_.clear(); |
---|
11 | } |
---|
12 | |
---|
13 | void ESCTest::positionCallback(const std_msgs::Float32MultiArray::ConstPtr &msg) |
---|
14 | { |
---|
15 | pos_ = msg->data; |
---|
16 | vel_.clear(); |
---|
17 | } |
---|
18 | |
---|
19 | void 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 | |
---|
31 | void 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 | |
---|
43 | void ESCTest::spin() |
---|
44 | { |
---|
45 | ROS_INFO("Spinning"); |
---|
46 | |
---|
47 | ros::Rate loop_rate(100); |
---|
48 | while (nh_.ok()) |
---|
49 | { |
---|
50 | if (!vel_.empty()) |
---|
51 | system_->step(vel_); |
---|
52 | else if (!pos_.empty()) |
---|
53 | system_->set(pos_); |
---|
54 | publish(); |
---|
55 | |
---|
56 | loop_rate.sleep(); |
---|
57 | ros::spinOnce(); |
---|
58 | } |
---|
59 | } |
---|
60 | |
---|
61 | int main(int argc, char **argv) |
---|
62 | { |
---|
63 | ros::init(argc, argv, "esc_test"); |
---|
64 | |
---|
65 | ESCFunction *function; |
---|
66 | |
---|
67 | if (argc > 1 && strcmp(argv[1], "-2") == 0) |
---|
68 | { |
---|
69 | std::vector<float> mean, sigma; |
---|
70 | mean.push_back(0.5); |
---|
71 | mean.push_back(0.2); |
---|
72 | sigma.push_back(0.15); |
---|
73 | sigma.push_back(0.15); |
---|
74 | function = new Gauss2D(2, -1, mean, sigma); |
---|
75 | } |
---|
76 | else |
---|
77 | function = new Gauss1D(2.5, -1.5, 0.4, 0.27/sqrt(2.0)); |
---|
78 | |
---|
79 | ESCTest test; |
---|
80 | |
---|
81 | test.init(new ESCSystem(function)); |
---|
82 | test.spin(); |
---|
83 | |
---|
84 | return 0; |
---|
85 | } |
---|