Skip to content

Commit

Permalink
Print less things
Browse files Browse the repository at this point in the history
  • Loading branch information
pittras committed Jul 10, 2018
1 parent f292196 commit 36c73ba
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 17 deletions.
18 changes: 9 additions & 9 deletions include/iarc7_fc_comms/CommonFcComms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,9 +240,9 @@ CommonFcComms<T>& CommonFcComms<T>::getInstance()
template<class T>
FcCommsReturns CommonFcComms<T>::init()
{
ROS_INFO("fc_comms_msp: Forming bond with safety client");
ROS_DEBUG("fc_comms_msp: Forming bond with safety client");
ROS_ASSERT_MSG(safety_client_.formBond(), "fc_comms_msp: Could not form bond with safety client");
ROS_INFO("fc_comms_msp: Formed bond with safety client");
ROS_DEBUG("fc_comms_msp: Formed bond with safety client");

uav_arm_service = nh_.advertiseService("uav_arm",
&CommonFcComms::uavArmServiceHandler,
Expand Down Expand Up @@ -293,7 +293,7 @@ FcCommsReturns CommonFcComms<T>::init()
&CommonFcComms::landingDetectedMessageHandler,
this);

ROS_INFO("FC Comms registered and subscribed to topics");
ROS_DEBUG("FC Comms registered and subscribed to topics");

if (calibrate_accelerometer_)
{
Expand All @@ -314,7 +314,7 @@ FcCommsReturns CommonFcComms<T>::init()
}
else
{
ROS_INFO("FC Comms received initial landing detected message succesfully");
ROS_DEBUG("FC Comms received initial landing detected message succesfully");
}

}
Expand Down Expand Up @@ -346,7 +346,7 @@ bool CommonFcComms<T>::uavArmServiceHandler(
iarc7_msgs::Arm::Request& request,
iarc7_msgs::Arm::Response& response)
{
ROS_INFO("Uav arm service handler called");
ROS_DEBUG("Uav arm service handler called");

bool auto_pilot;
FcCommsReturns status = flightControlImpl_.isAutoPilotAllowed(auto_pilot);
Expand All @@ -358,7 +358,7 @@ bool CommonFcComms<T>::uavArmServiceHandler(
// If auto pilot is not enabled we have no power
if(!auto_pilot)
{
ROS_INFO("Failed to arm or disarm the FC: auto pilot is disabled");
ROS_ERROR("Failed to arm or disarm the FC: auto pilot is disabled");
response.success = false;
response.message = "disabled";
return true;
Expand All @@ -382,7 +382,7 @@ bool CommonFcComms<T>::uavArmServiceHandler(
if (status == FcCommsReturns::kReturnOk) {
if(armed == request.data)
{
ROS_INFO("FC arm or disarm set succesfully");
ROS_DEBUG("FC arm or disarm set succesfully");

status = flightControlImpl_.postArm(request.data);
if(status != FcCommsReturns::kReturnOk) {
Expand All @@ -401,7 +401,7 @@ bool CommonFcComms<T>::uavArmServiceHandler(
update();
}

ROS_INFO("Failed to arm or disarm the FC: timed out");
ROS_ERROR("Failed to arm or disarm the FC: timed out");
response.success = false;
response.message = "timed out";
return true;
Expand Down Expand Up @@ -573,7 +573,7 @@ void CommonFcComms<T>::reconnect() {

if(status == FcCommsReturns::kReturnOk)
{
ROS_INFO("iarc7_fc_comms: Succesful reconnection to flight controller");
ROS_DEBUG("iarc7_fc_comms: Succesful reconnection to flight controller");
calibrateAccelerometer();
}
else
Expand Down
2 changes: 1 addition & 1 deletion src/Msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ int main(int argc, char **argv)
{
ros::init(argc, argv, "FC_comms");

ROS_INFO("FC_comms begin");
ROS_DEBUG("FC_comms begin");

CommonFcComms<MspFcComms>& fc = CommonFcComms<MspFcComms>::getInstance();

Expand Down
14 changes: 7 additions & 7 deletions src/MspFcComms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ FcCommsReturns MspFcComms::getAttitude(double (&attitude)[3])

FcCommsReturns MspFcComms::calibrateAccelerometer()
{
ROS_INFO("Starting accelerometer calibration");
ROS_DEBUG("Starting accelerometer calibration");
MSP_ACC_CALIBRATION cal;
FcCommsReturns status = sendMessage(cal);

Expand All @@ -248,15 +248,15 @@ FcCommsReturns MspFcComms::calibrateAccelerometer()
rate.sleep();
}

ROS_INFO("Done accelerometer calibration");
ROS_DEBUG("Done accelerometer calibration");

return status;
}

// Disconnect from FC, should be called before destructor.
FcCommsReturns MspFcComms::disconnect()
{
ROS_INFO("Disconnecting from FC");
ROS_DEBUG("Disconnecting from FC");

// Handle each connection state seperately.
switch(fc_comms_status_)
Expand All @@ -281,7 +281,7 @@ FcCommsReturns MspFcComms::disconnect()
return FcCommsReturns::kReturnError;
}

ROS_INFO("Succesfull disconnection from FC");
ROS_DEBUG("Succesfull disconnection from FC");

fc_comms_status_ = FcCommsStatus::kDisconnected;
return FcCommsReturns::kReturnOk;
Expand All @@ -292,7 +292,7 @@ FcCommsReturns MspFcComms::connect()
{
try
{
ROS_INFO("FC_Comms beginning connection");
ROS_DEBUG("FC_Comms beginning connection");
fc_comms_status_ = FcCommsStatus::kConnecting;

// Find the flight controller by the hardware ID.
Expand Down Expand Up @@ -325,7 +325,7 @@ FcCommsReturns MspFcComms::connect()
rate.sleep();
}

ROS_INFO("FC_Comms Connected to FC");
ROS_DEBUG("FC_Comms Connected to FC");
fc_comms_status_ = FcCommsStatus::kConnected;

return FcCommsReturns::kReturnOk;
Expand Down Expand Up @@ -377,7 +377,7 @@ FcCommsReturns MspFcComms::findFc(std::string& serial_port)
// If we've found something with the same hardware id as our FC
if(device.hardware_id == FcCommsMspConf::kHardwareId)
{
ROS_INFO("FC_comms found target device.");
ROS_DEBUG("FC_comms found target device.");
serial_port = device.port;

// Exit loop since we've found the port
Expand Down

0 comments on commit 36c73ba

Please sign in to comment.