Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
A
axis_imu
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Iterations
Requirements
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Locked files
Build
Pipelines
Jobs
Pipeline schedules
Test cases
Artifacts
Deploy
Releases
Package registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Code review analytics
Issue analytics
Insights
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
axis
axis_imu
Commits
05d4773a
Commit
05d4773a
authored
6 years ago
by
Tommy Persson
Browse files
Options
Downloads
Patches
Plain Diff
Cleanup.
parent
26461f60
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/axis_imu.cc
+4
-17
4 additions, 17 deletions
src/axis_imu.cc
with
4 additions
and
17 deletions
src/axis_imu.cc
+
4
−
17
View file @
05d4773a
...
...
@@ -23,21 +23,8 @@ sensor_msgs::Imu imu_msg;
boost
::
mutex
mutex
;
// 1 byte header ('A' eller 'G') | float64 timestamp | float64 x | float64 y | float64 z
//
// Headern 'A' och 'G' står för accelerometer respektive gyro.
// timestamp är sekunder sedan kamerans uppstart
// x, y och z är i grader/s för gyrot och G för accelerometern.
//
// 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.
//
// Fix rate ut, 1kHz
...
...
@@ -54,7 +41,7 @@ void handler(const boost::system::error_code& error,
}
void
spin_thread
()
{
ROS_ERROR
(
"Before Spin in spin_thread"
);
//
ROS_ERROR("Before Spin in spin_thread");
ros
::
spin
();
}
...
...
@@ -124,11 +111,11 @@ private:
az
=
bytesToDouble
(
58
);
if
(
recv_buffer_
[
0
]
==
'G'
)
{
have_gyro_flag
=
true
;
ROS_ERROR
(
" GYRO: %f - %f %f %f"
,
gtime
,
gx
,
gy
,
gz
);
//
ROS_ERROR(" GYRO: %f - %f %f %f", gtime, gx, gy, gz);
}
if
(
recv_buffer_
[
33
]
==
'A'
)
{
have_acc_flag
=
true
;
ROS_ERROR
(
"ACCELEROMETER: %f - %f %f %f"
,
atime
,
ax
,
ay
,
az
);
//
ROS_ERROR("ACCELEROMETER: %f - %f %f %f", atime, ax, ay, az);
}
if
(
!
have_gyro_flag
)
{
...
...
@@ -321,7 +308,7 @@ int main(int argc, char *argv[]) {
boost
::
thread
sthread
(
spin_thread
);
ROS_
ERROR
(
"runUDPServer"
);
ROS_
INFO
(
"runUDPServer"
);
runUDPServer
(
port
);
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment