Skip to content
Snippets Groups Projects
Commit 559818b8 authored by Tommy Persson's avatar Tommy Persson
Browse files

Adding parameters.

parent b19579f7
No related branches found
No related tags found
No related merge requests found
......@@ -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);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment