Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

navdata_packet.header now filled, also using cmd_vel.angular.x/y != 0 for hover #38

Merged
merged 2 commits into from
Nov 23, 2012
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions launch/ardrone_aggressive.launch
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,6 @@
<param name="do_imu_caliberation" value="false" />
<param name="tf_prefix" value="mydrone" />

<param name="command_disable_hover" value="true" />
<param name="command_always_send" value="true" />

<param name="enable_navdata_demo" value="true" />
<param name="enable_navdata_time" value="true" />
<param name="enable_navdata_raw_measures" value="true" />
Expand Down
14 changes: 9 additions & 5 deletions scripts/NavdataMessageDefinitionsTemplate.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
% for item in structs:
ros::Publisher pub_${item['struct_name']};
bool enabled_${item['struct_name']};
ardrone_autonomy::${item['struct_name']} ${item['struct_name']}_msg;
% endfor

bool enabled_legacy_navdata;
Expand All @@ -30,6 +31,8 @@
#ifdef NAVDATA_STRUCTS_SOURCE
void ARDroneDriver::PublishNavdataTypes(navdata_unpacked_t n)
{
const ros::Time now = ros::Time::now();

if(!initialized_navdata_publishers)
{
initialized_navdata_publishers = true;
Expand Down Expand Up @@ -63,26 +66,27 @@ void ARDroneDriver::PublishNavdataTypes(navdata_unpacked_t n)
% for item in structs:
if(enabled_${item['struct_name']} && pub_${item['struct_name']}.getNumSubscribers()>0)
{
ardrone_autonomy::${item['struct_name']} msg;
msg.drone_time = ((double)ardrone_time_to_usec(n.navdata_time.time))/1000000.0;
${item['struct_name']}_msg.drone_time = ((double)ardrone_time_to_usec(n.navdata_time.time))/1000000.0;
${item['struct_name']}_msg.header.stamp = now;
${item['struct_name']}_msg.header.frame_id = droneFrameBase;

% for member in item['members']:
% if member['array_size'] is None:
{\
${format_member(item, member, None)}
msg.${member['name']} = m;
${item['struct_name']}_msg.${member['name']} = m;
}

% else:
for(int i=0; i<${member['array_size']}; i++)
{\
${format_member(item, member, 'i')}
msg.${member['name']}.push_back(m);
${item['struct_name']}_msg.${member['name']}.push_back(m);
}

% endif
% endfor
pub_${item['struct_name']}.publish(msg);
pub_${item['struct_name']}.publish(${item['struct_name']}_msg);
}

//-------------------------
Expand Down
Loading