diff --git a/src/axis_imu.cc b/src/axis_imu.cc
index 250d31018ef40f323456c69c295f756ef7bbcf3d..6e3a0b75b6f68dfa28f8b0be946856c58cf9d51d 100644
--- a/src/axis_imu.cc
+++ b/src/axis_imu.cc
@@ -26,6 +26,15 @@ ros::Publisher imu_pub;
 //
 // Data sent in network byte order
 //
+// Jag använder följande curl-kommando för att starta
+// curl --digest "[http://root:pass@[IP]/local/motionloggerudp/control.cgi?cmd=start&target_ip=10.92.1.19&accel_enabled=1&accel_rate_div=0&gyro_enabled=1&gyro_rate_div=0]http://root:pass@[IP]/local/motionloggerudp/control.cgi?cmd=start&target_ip=10.92.1.19&accel_enabled=1&accel_rate_div=0&gyro_enabled=1&gyro_rate_div=0"
+//
+// För att starta motionloggerudp (som är vad jag har kallat den nya varianten som inte lagrar på SD-kort) så anropar man t.ex.
+// http://[CAMERAIP]/local/motionloggerudp/control.cgi?cmd=start&target_ip=[TARGETIP]&accel_enabled=1&accel_rate_div=0&gyro_enabled=1&gyro_rate_div=0
+//
+// Max sample rate för gyrot är 2kHz och för accelerometern 1kHz, och detta styrs med gyro_rate_div och accel_rate_div i ovanstående http-anrop.
+//
+
 
 
 using namespace std;
@@ -212,10 +221,31 @@ int main(int argc, char *argv[]) {
 
   int port;
   int rate;
+  std::string camera_ip;
+  std::string driver_ip;
 
   private_nh.param<int>("port", port, 5000);
   private_nh.param<std::string>("frame_id", frame_id, "imu");
-  private_nh.param("rate", rate, 200);
+  private_nh.param<int>("rate", rate, 200);
+  private_nh.param<std::string>("camera_ip", camera_ip, "192.168.7.19");
+  private_nh.param<std::string>("driver_ip", driver_ip, "192.168.7.160");
+
+  ROS_INFO("Camera IP: %s", camera_ip.c_str());
+  ROS_INFO("Driver IP: %s", driver_ip.c_str());
+  ROS_INFO("     Port: %d", port);
+  ROS_INFO(" Frame Id: %s", frame_id.c_str());
+  ROS_INFO("     Rate: %d", rate);
+
+  int gyro_div = 2000/rate;
+  int accel_div = 1000/rate;
+
+  std::ostringstream os;
+
+  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();
+
+  ROS_INFO("COMMAND URL: %s", url.c_str());
 
   imu_pub = nh.advertise<sensor_msgs::Imu>("imu",1);