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

Adding _pos_enabled parameter

parent d418e140
No related branches found
No related tags found
No related merge requests found
......@@ -2,20 +2,22 @@
Driver to Axis IMU.
Use app file: motionloggerudp_0_6-0_mipsisa32r2el.eap
Use app file: motionloggerudp_0_6-1_mipsisa32r2el.eap
at least.
Usage:
```bash
rosrun axis_imu axis_imu _frame_id:=imu_frame _rate:=100 _root_passwd:=pass _camera_ip:=192.168.7.205 _driver_ip:=192.168.7.160 _port:=5000
rosrun axis_imu axis_imu _frame_id:=imu_frame _rate:=100 _root_passwd:=pass _camera_ip:=192.168.7.205 _driver_ip:=192.168.7.160 _port:=5000 _pos_enabled:=0
```
The port specification only works the first time. To get it to work
again go to the app section in the camera and stop and start the
motionloggerudp app.
The orientation is not filled in since I do not get sensible values from my camera.
The orientation is not filled in since I do not get sensible values
from my camera. The POSITION is really the pan tilt value so should
not be used as imu rotaation.
Patch the code if you need.
......@@ -254,6 +254,7 @@ int main(int argc, char *argv[]) {
int port;
int rate;
int pos_enabled;
std::string camera_ip;
std::string driver_ip;
std::string root_passwd;
......@@ -261,16 +262,18 @@ int main(int argc, char *argv[]) {
private_nh.param<int>("port", port, 5000);
private_nh.param<std::string>("frame_id", frame_id, "imu");
private_nh.param<int>("rate", rate, 200);
private_nh.param<int>("pos_enabled", pos_enabled, 0);
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");
private_nh.param<std::string>("root_passwd", root_passwd, "pass");
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);
ROS_INFO("Root pass: %s", root_passwd.c_str());
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);
ROS_INFO("Pos Enabled: %d", pos_enabled);
ROS_INFO(" Root pass: %s", root_passwd.c_str());
int gyro_div = 2000/rate;
int accel_div = 1000/rate;
......@@ -289,7 +292,7 @@ int main(int argc, char *argv[]) {
os << "http://" << camera_ip
<< "/local/motionloggerudp/control.cgi?cmd=start&target_ip=" << driver_ip
<< "&target_port=" << port
<< "&accel_enabled=1&accel_rate_div=" << accel_div << "&gyro_enabled=1&gyro_rate_div=" << gyro_div << "&pos_enabled=1"
<< "&accel_enabled=1&accel_rate_div=" << accel_div << "&gyro_enabled=1&gyro_rate_div=" << gyro_div << "&pos_enabled=" << pos_enabled
;
std::string stopurl = osstop.str();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment