Revision 122a57d8 quad2/altitude_node/src/altitude_node.cpp

View differences:

quad2/altitude_node/src/altitude_node.cpp
32 32
  enable_sub = n.subscribe<std_msgs::Bool>("/altitude_node/enable",
33 33
      100, &AltitudeNode::enable_cb, this);
34 34
  pub = n.advertise<std_msgs::Float64>("/mikrokopter/thrust", 100);
35
  
36
  float default_goal;
37
  ros::param::param<float>("~default_goal", default_goal, 0);
38
  pid.change_goal(default_goal);
35 39
}
36 40

  
37 41
void AltitudeNode::height_cb(const mikrokopter::FcDebug::ConstPtr& fc)

Also available in: Unified diff