42 #include <std_msgs/Float64.h>
66 int main(
int argc,
char** argv)
70 double displacement = 3.3;
77 ROS_INFO(
"Plant_sim spinning waiting for time to become non-zero");
82 node_priv.
param<
int>(
"plant_order", plant_order, 1);
87 ROS_INFO(
"Starting simulation of a first-order plant.");
89 else if (plant_order == 2)
91 ROS_INFO(
"Starting simulation of a second-order plant.");
95 ROS_ERROR(
"Error: Invalid plant type parameter, must be 1 or 2: %s", argv[1]);
100 std_msgs::Float64 plant_state;
106 int loop_counter = 0;
107 double delta_t = 0.01;
111 double temp_rate = 0;
115 double acceleration = 0;
117 double friction = 1.0;
131 temp = temp + temp_rate * delta_t;
133 plant_state.data = temp;
137 if (fabs(speed) < 0.001)
155 decel_force = -(speed * friction);
156 acceleration = ((Kv * (
control_effort - (Kbackemf * speed)) + decel_force) / mass);
157 speed = speed + (acceleration * delta_t);
158 displacement = displacement + speed * delta_t;
160 plant_state.data = displacement;
164 ROS_ERROR(
"Invalid plant_order: %d", plant_order);
168 servo_state_pub.
publish(plant_state);