diff --git a/src/axis_imu.cc b/src/axis_imu.cc index 65d1b6e993a155de870fc28789bcc1cc0fd47763..4c30a62cbaeac403c7e905915c400aa82ecaaf3e 100644 --- a/src/axis_imu.cc +++ b/src/axis_imu.cc @@ -219,7 +219,7 @@ void runUDPServer(int port) { int main(int argc, char *argv[]) { ros::init(argc, argv, "axis_imu"); - ros::NodeHandle nh, private_nh; + ros::NodeHandle nh, private_nh("~"); int port; int rate; @@ -246,7 +246,8 @@ int main(int argc, char *argv[]) { std::ostringstream os; - os << "http://" << "root:" << root_passwd << "@" << camera_ip + // os << "http://" << "root:" << root_passwd << "@" << camera_ip + os << "http://" << camera_ip << "/local/motionloggerudp/control.cgi?cmd=start&target_ip=" << driver_ip << "&accel_enabled=1&accel_rate_div=" << accel_div << "&gyro_enabled=1&gyro_rate_div=" << gyro_div; std::string url = os.str(); @@ -264,9 +265,12 @@ int main(int argc, char *argv[]) { /* Perform the request, res will get the return code */ res = curl_easy_perform(curl); /* Check for errors */ - if(res != CURLE_OK) + if(res != CURLE_OK) { fprintf(stderr, "curl_easy_perform() failed: %s\n", curl_easy_strerror(res)); + } else { + ROS_INFO("Curl call succeeded"); + } /* always cleanup */ curl_easy_cleanup(curl);