From 25456e3b806579a92c908e7c45707ec6ae52b6aa Mon Sep 17 00:00:00 2001 From: jb Date: Fri, 27 Apr 2012 15:55:06 +0100 Subject: [PATCH 001/508] GCS - Added support for map ripping --- .../src/mapwidget/mapgraphicitem.cpp | 8 +-- .../opmapcontrol/src/mapwidget/mapripper.cpp | 63 ++++++++++++------- .../opmapcontrol/src/mapwidget/mapripper.h | 1 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 13 ++++ .../src/plugins/opmap/opmapgadgetwidget.h | 2 + 5 files changed, 60 insertions(+), 27 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 7c7984aa0..1df30d653 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -196,7 +196,7 @@ namespace mapcontrol } } - else if(isSelected && !selectionStart.IsEmpty() && (event->modifiers() == Qt::AltModifier || event->modifiers() == Qt::ShiftModifier)) + else if(isSelected && !selectionStart.IsEmpty() && (event->modifiers() == Qt::ControlModifier || event->modifiers() == Qt::ShiftModifier)) { selectionEnd = FromLocalToLatLng(event->pos().x(), event->pos().y()); { @@ -217,10 +217,10 @@ namespace mapcontrol { - + qDebug()<modifiers(); if(!IsMouseOverMarker()) { - if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::AltModifier)||(event->modifiers()==Qt::ShiftModifier))) + if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) { core->mouseDown.SetX(event->pos().x()); core->mouseDown.SetY(event->pos().y()); @@ -232,7 +232,7 @@ namespace mapcontrol this->update(); } - else if(!isSelected && ((event->modifiers()==Qt::AltModifier)||(event->modifiers()==Qt::ShiftModifier))) + else if(!isSelected && ((event->modifiers()==Qt::ControlModifier)||(event->modifiers()==Qt::ShiftModifier))) { isSelected = true; SetSelectedArea (internals::RectLatLng::Empty); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 00a2053cd..41518b81f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -28,7 +28,7 @@ namespace mapcontrol { - MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core) +MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core),yesToAll(false) { if(!rect.IsEmpty()) { @@ -46,32 +46,49 @@ namespace mapcontrol connect(this,SIGNAL(finished()),this,SLOT(finish())); emit numberOfTilesChanged(0,0); } + else + QMessageBox::information(new QWidget(),"No valid selection","Please select the area of the map to rip with Mouse+Control key"); } - void MapRipper::finish() +void MapRipper::finish() +{ + if(zoomProjection()->GetAreaTileList(area,zoom,0); - this->start(); - } - else - { - progressForm->close(); - delete progressForm; - this->deleteLater(); - } - } + QMessageBox msgBox; + msgBox.setText(QString("Continue Ripping at zoom level %1?").arg(zoom)); + // msgBox.setInformativeText("Do you want to save your changes?"); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::YesAll); + msgBox.setDefaultButton(QMessageBox::Yes); + ret = msgBox.exec(); + } + else + ret=QMessageBox::Yes; + if(ret==QMessageBox::Yes) + { + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else if(ret==QMessageBox::YesAll) + { + yesToAll=true; + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else + { + progressForm->close(); + delete progressForm; + this->deleteLater(); + } } + else + yesToAll=false; +} void MapRipper::run() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index 6b2087a12..313156863 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -50,6 +50,7 @@ namespace mapcontrol MapRipForm * progressForm; int maxzoom; internals::Core * core; + bool yesToAll; signals: void percentageChanged(int const& perc); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index c0a07a000..540a387c7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -431,6 +431,10 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addAction(reloadAct); + menu.addSeparator(); + + menu.addAction(ripAct); + menu.addSeparator(); QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); @@ -1413,6 +1417,10 @@ void OPMapGadgetWidget::createActions() reloadAct->setStatusTip(tr("Reload the map tiles")); connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); + ripAct = new QAction(tr("&Rip map"), this); + ripAct->setStatusTip(tr("Rip the map tiles")); + connect(ripAct, SIGNAL(triggered()), this, SLOT(onRipAct_triggered())); + copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this); copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard")); connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered())); @@ -1685,6 +1693,11 @@ void OPMapGadgetWidget::onReloadAct_triggered() m_map->ReloadMap(); } +void OPMapGadgetWidget::onRipAct_triggered() +{ + m_map->RipMap(); +} + void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() { QClipboard *clipboard = QApplication::clipboard(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 24f638a80..8d374acdc 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -187,6 +187,7 @@ private slots: * @brief mouse right click context menu signals */ void onReloadAct_triggered(); + void onRipAct_triggered(); void onCopyMouseLatLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLonToClipAct_triggered(); @@ -282,6 +283,7 @@ private: QAction *closeAct1; QAction *closeAct2; QAction *reloadAct; + QAction *ripAct; QAction *copyMouseLatLonToClipAct; QAction *copyMouseLatToClipAct; QAction *copyMouseLonToClipAct; From c95eeb92bbb60624f2863013ed429e92ed849443 Mon Sep 17 00:00:00 2001 From: jb Date: Mon, 30 Apr 2012 14:57:06 +0100 Subject: [PATCH 002/508] GCS some improvements to the ripping function of the map library. --- .../opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 7 ------- .../opmapcontrol/src/mapwidget/mapripform.cpp | 1 + .../libs/opmapcontrol/src/mapwidget/mapripform.h | 2 ++ .../libs/opmapcontrol/src/mapwidget/mapripform.ui | 8 ++++---- .../libs/opmapcontrol/src/mapwidget/mapripper.cpp | 15 ++++++++++++++- .../libs/opmapcontrol/src/mapwidget/mapripper.h | 2 ++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 8 +++++--- 7 files changed, 28 insertions(+), 15 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 1df30d653..d4c548015 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -216,8 +216,6 @@ namespace mapcontrol void MapGraphicItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { - - qDebug()<modifiers(); if(!IsMouseOverMarker()) { if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) @@ -431,11 +429,6 @@ namespace mapcontrol } } } - // painter->drawRect(core->GetrenderOffset().X()-lastimagepoint.X()-3,core->GetrenderOffset().Y()-lastimagepoint.Y()-3,lastimage.width(),lastimage.height()); -// painter->setPen(Qt::red); -// painter->drawLine(-10,-10,10,10); -// painter->drawLine(10,10,-10,-10); -// painter->drawRect(boundingRect().adjusted(100,100,-100,-100)); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp index bbd1725a1..b2baf5b21 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp @@ -33,6 +33,7 @@ MapRipForm::MapRipForm(QWidget *parent) : ui(new Ui::MapRipForm) { ui->setupUi(this); + connect(ui->cancelButton,SIGNAL(clicked()),this,SIGNAL(cancelRequest())); } MapRipForm::~MapRipForm() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h index b1ff3637f..6f150fd4d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h @@ -44,6 +44,8 @@ public slots: void SetPercentage(int const& perc); void SetProvider(QString const& prov,int const& zoom); void SetNumberOfTiles(int const& total,int const& actual); +signals: + void cancelRequest(); private: Ui::MapRipForm *ui; }; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui index 8100f8651..1fa6a935d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui @@ -6,7 +6,7 @@ 0 0 - 392 + 521 133 @@ -18,7 +18,7 @@ 20 60 - 371 + 481 23 @@ -31,7 +31,7 @@ 30 10 - 321 + 481 16 @@ -55,7 +55,7 @@ - 280 + 220 100 75 23 diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 41518b81f..bbda543d6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -34,11 +34,13 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect) { type=core->GetMapType(); progressForm=new MapRipForm; + connect(progressForm,SIGNAL(cancelRequest()),this,SLOT(stopFetching())); area=rect; zoom=core->Zoom(); maxzoom=core->MaxZoom(); points=core->Projection()->GetAreaTileList(area,zoom,0); this->start(); + cancel=false; progressForm->show(); connect(this,SIGNAL(percentageChanged(int)),progressForm,SLOT(SetPercentage(int))); connect(this,SIGNAL(numberOfTilesChanged(int,int)),progressForm,SLOT(SetNumberOfTiles(int,int))); @@ -51,7 +53,7 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect) } void MapRipper::finish() { - if(zoomclose(); + delete progressForm; + this->deleteLater(); + } } @@ -136,4 +143,10 @@ void MapRipper::finish() QThread::msleep(sleep); } } + + void MapRipper::stopFetching() + { + QMutexLocker locker(&mutex); + cancel=true; + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index 313156863..2c426d3d1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -51,6 +51,7 @@ namespace mapcontrol int maxzoom; internals::Core * core; bool yesToAll; + QMutex mutex; signals: void percentageChanged(int const& perc); @@ -59,6 +60,7 @@ namespace mapcontrol public slots: + void stopFetching(); void finish(); }; } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 540a387c7..78c70837f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -477,12 +477,14 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); */ - - menu.addAction(showSafeAreaAct); + QMenu safeArea("Safety Area definitions"); + // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); for (int i = 0; i < safeAreaAct.count(); i++) safeAreaSubMenu.addAction(safeAreaAct.at(i)); - menu.addMenu(&safeAreaSubMenu); + safeArea.addMenu(&safeAreaSubMenu); + safeArea.addAction(showSafeAreaAct); + menu.addMenu(&safeArea); menu.addSeparator(); From 74d96d0073b705224e9b402f44a2ba1b76ce5ff8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 8 May 2012 16:22:06 +0100 Subject: [PATCH 003/508] Minor cleaning --- .../opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 12 +++++++++++- .../libs/opmapcontrol/src/mapwidget/mapgraphicitem.h | 2 ++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index d4c548015..91623b03f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -40,6 +40,7 @@ namespace mapcontrol core->SetCurrentRegion(internals::Rectangle(0, 0, maprect.width(), maprect.height())); core->SetMapType(MapType::GoogleHybrid); this->SetZoom(2); + this->setFlag(ItemIsFocusable); connect(core,SIGNAL(OnNeedInvalidation()),this,SLOT(Core_OnNeedInvalidation())); connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh())); connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); @@ -238,7 +239,6 @@ namespace mapcontrol selectionStart = FromLocalToLatLng(event->pos().x(), event->pos().y()); } } - } void MapGraphicItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { @@ -272,6 +272,16 @@ namespace mapcontrol } } + void MapGraphicItem::keyPressEvent(QKeyEvent *event) + { + if(event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier)) + this->setCursor(Qt::CrossCursor); + } + void MapGraphicItem::keyReleaseEvent(QKeyEvent *event) + { + if((event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier))==0) + this->setCursor(Qt::ArrowCursor); + } bool MapGraphicItem::SetZoomToFitRect(internals::RectLatLng const& rect) { int maxZoom = core->GetMaxZoomToFitRect(rect); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index 034b1c8b8..c3c235617 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -107,6 +107,8 @@ namespace mapcontrol void wheelEvent ( QGraphicsSceneWheelEvent * event ); void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); bool IsMouseOverMarker()const{return isMouseOverMarker;} + void keyPressEvent ( QKeyEvent * event ); + void keyReleaseEvent ( QKeyEvent * event ); /** * @brief Returns current map zoom From fa20b0de63a46862a049737755c9d5318342c75d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 11 May 2012 19:20:35 -0500 Subject: [PATCH 004/508] Fix indentation in the map gadget widget before starting work on waypoints --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 1032 ++++++++--------- 1 file changed, 516 insertions(+), 516 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 78c70837f..8cb4670f4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -7,7 +7,7 @@ * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin * @{ - * @brief The OpenPilot Map plugin + * @brief The OpenPilot Map plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -90,60 +90,60 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_mouse_waypoint = NULL; - pm = NULL; - obm = NULL; - obum = NULL; + pm = NULL; + obm = NULL; + obum = NULL; - m_prev_tile_number = 0; + m_prev_tile_number = 0; - m_min_zoom = m_max_zoom = 0; + m_min_zoom = m_max_zoom = 0; m_map_mode = Normal_MapMode; - m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds + m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds - m_telemetry_connected = false; + m_telemetry_connected = false; - m_context_menu_lat_lon = m_mouse_lat_lon = internals::PointLatLng(0, 0); + m_context_menu_lat_lon = m_mouse_lat_lon = internals::PointLatLng(0, 0); setMouseTracking(true); - pm = ExtensionSystem::PluginManager::instance(); - if (pm) - { - obm = pm->getObject(); - obum = pm->getObject(); - } + pm = ExtensionSystem::PluginManager::instance(); + if (pm) + { + obm = pm->getObject(); + obum = pm->getObject(); + } - // ************** + // ************** // get current location double latitude = 0; double longitude = 0; double altitude = 0; - // current position - getUAVPosition(latitude, longitude, altitude); + // current position + getUAVPosition(latitude, longitude, altitude); internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude); // ************** // default home position - m_home_position.coord = pos_lat_lon; - m_home_position.altitude = altitude; - m_home_position.locked = false; + m_home_position.coord = pos_lat_lon; + m_home_position.altitude = altitude; + m_home_position.locked = false; // ************** // default magic waypoint params - m_magic_waypoint.map_wp_item = NULL; - m_magic_waypoint.coord = m_home_position.coord; - m_magic_waypoint.altitude = altitude; - m_magic_waypoint.description = "Magic waypoint"; - m_magic_waypoint.locked = false; - m_magic_waypoint.time_seconds = 0; - m_magic_waypoint.hold_time_seconds = 0; + m_magic_waypoint.map_wp_item = NULL; + m_magic_waypoint.coord = m_home_position.coord; + m_magic_waypoint.altitude = altitude; + m_magic_waypoint.description = "Magic waypoint"; + m_magic_waypoint.locked = false; + m_magic_waypoint.time_seconds = 0; + m_magic_waypoint.hold_time_seconds = 0; // ************** // create the widget that holds the user controls and the map @@ -164,8 +164,8 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->horizontalSliderZoom->setMinimum(m_map->MinZoom()); // m_widget->horizontalSliderZoom->setMaximum(m_map->MaxZoom() + max_digital_zoom); // - m_min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept - m_max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept + m_min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept + m_max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions m_map->SetFollowMouse(true); // we want a contiuous mouse position reading @@ -173,20 +173,20 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->SetShowHome(true); // display the HOME position on the map m_map->SetShowUAV(true); // display the UAV position on the map - m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) + m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) m_map->Home->SetShowSafeArea(true); // show the safe area m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->UAV->SetTrailType(UAVTrailType::ByDistance); + // m_map->UAV->SetTrailType(UAVTrailType::ByDistance); m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->GPS->SetTrailType(UAVTrailType::ByDistance); + // m_map->GPS->SetTrailType(UAVTrailType::ByDistance); // ************** @@ -205,24 +205,24 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) switch (m_map_mode) { - case Normal_MapMode: - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); - break; + case Normal_MapMode: + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + hideMagicWaypointControls(); + break; - case MagicWaypoint_MapMode: - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - showMagicWaypointControls(); - break; + case MagicWaypoint_MapMode: + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + showMagicWaypointControls(); + break; - default: - m_map_mode = Normal_MapMode; - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); - break; + default: + m_map_mode = Normal_MapMode; + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + hideMagicWaypointControls(); + break; } m_widget->labelUAVPos->setText("---"); @@ -241,12 +241,12 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->progressBarMap->setMaximum(1); -/* + /* #if defined(Q_OS_MAC) #elif defined(Q_OS_WIN) - m_widget->comboBoxFindPlace->clear(); - loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); - m_widget->comboBoxFindPlace->setCurrentIndex(-1); + m_widget->comboBoxFindPlace->clear(); + loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); + m_widget->comboBoxFindPlace->setCurrentIndex(-1); #else #endif */ @@ -269,10 +269,10 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); - m_map->SetCurrentPosition(m_home_position.coord); // set the map position - m_map->Home->SetCoord(m_home_position.coord); // set the HOME position - m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + m_map->SetCurrentPosition(m_home_position.coord); // set the map position + m_map->Home->SetCoord(m_home_position.coord); // set the HOME position + m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position // ************** // create various context menu (mouse right click menu) actions @@ -287,10 +287,10 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) // Register for Home Location state changes if (obm) { - UAVDataObject *obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); + UAVDataObject *obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); if (obj) { - connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); } } @@ -307,14 +307,14 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) // create the desired timers m_updateTimer = new QTimer(); - m_updateTimer->setInterval(m_maxUpdateRate); + m_updateTimer->setInterval(m_maxUpdateRate); connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updatePosition())); m_updateTimer->start(); m_statusUpdateTimer = new QTimer(); - m_statusUpdateTimer->setInterval(200); -// m_statusUpdateTimer->setInterval(m_maxUpdateRate); - connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); + m_statusUpdateTimer->setInterval(200); + // m_statusUpdateTimer->setInterval(m_maxUpdateRate); + connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); m_statusUpdateTimer->start(); // ************** @@ -325,21 +325,21 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) // destructor OPMapGadgetWidget::~OPMapGadgetWidget() { - if (m_map) - { - disconnect(m_map, 0, 0, 0); - m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit - m_map->SetShowUAV(false); // " " - } + if (m_map) + { + disconnect(m_map, 0, 0, 0); + m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit + m_map->SetShowUAV(false); // " " + } // this destructor doesn't appear to be called at shutdown??? -// #if defined(Q_OS_MAC) -// #elif defined(Q_OS_WIN) -// saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); -// #else -// #endif + // #if defined(Q_OS_MAC) + // #elif defined(Q_OS_WIN) + // saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); + // #else + // #endif m_waypoint_list_mutex.lock(); foreach (t_waypoint *wp, m_waypoint_list) @@ -355,11 +355,11 @@ OPMapGadgetWidget::~OPMapGadgetWidget() m_waypoint_list_mutex.unlock(); m_waypoint_list.clear(); - if (m_map) - { - delete m_map; - m_map = NULL; - } + if (m_map) + { + delete m_map; + m_map = NULL; + } } // ************************************************************************************* @@ -382,7 +382,7 @@ void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) if (event->buttons() & Qt::LeftButton) { -// QPoint pos = event->pos(); + // QPoint pos = event->pos(); } QWidget::mouseMoveEvent(event); @@ -393,22 +393,22 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) QString s; - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (event->reason() != QContextMenuEvent::Mouse) return; // not a mouse click event // current mouse position QPoint p = m_map->mapFromGlobal(event->globalPos()); - m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); -// m_context_menu_lat_lon = m_map->currentMousePosition(); + m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); + // m_context_menu_lat_lon = m_map->currentMousePosition(); if (!m_map->contentsRect().contains(p)) return; // the mouse click was not on the map // show the mouse position - s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7); + s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7); m_widget->labelMousePos->setText(s); // find out if we have a waypoint under the mouse cursor @@ -437,18 +437,18 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); - QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); - for (int i = 0; i < maxUpdateRateAct.count(); i++) - maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); - menu.addMenu(&maxUpdateRateSubMenu); + QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); + for (int i = 0; i < maxUpdateRateAct.count(); i++) + maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); + menu.addMenu(&maxUpdateRateSubMenu); - menu.addSeparator(); + menu.addSeparator(); switch (m_map_mode) { - case Normal_MapMode: s = tr(" (Normal)"); break; - case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break; - default: s = tr(" (Unknown)"); break; + case Normal_MapMode: s = tr(" (Normal)"); break; + case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break; + default: s = tr(" (Unknown)"); break; } for (int i = 0; i < mapModeAct.count(); i++) { // set the menu to checked (or not) @@ -478,7 +478,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); */ QMenu safeArea("Safety Area definitions"); - // menu.addAction(showSafeAreaAct); + // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); for (int i = 0; i < safeAreaAct.count(); i++) safeAreaSubMenu.addAction(safeAreaAct.at(i)); @@ -551,9 +551,9 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) switch (m_map_mode) { - case Normal_MapMode: + case Normal_MapMode: // only show the waypoint stuff if not in 'magic waypoint' mode - /* + /* menu.addSeparator()->setText(tr("Waypoints")); menu.addAction(wayPointEditorAct); @@ -576,12 +576,12 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) m_waypoint_list_mutex.unlock(); */ - break; + break; - case MagicWaypoint_MapMode: - menu.addSeparator()->setText(tr("Waypoints")); - menu.addAction(homeMagicWaypointAct); - break; + case MagicWaypoint_MapMode: + menu.addSeparator()->setText(tr("Waypoints")); + menu.addAction(homeMagicWaypointAct); + break; } // ********* @@ -601,32 +601,32 @@ void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event) switch (event->key()) { - case Qt::Key_Escape: - break; + case Qt::Key_Escape: + break; - case Qt::Key_F1: - break; + case Qt::Key_F1: + break; - case Qt::Key_F2: - break; + case Qt::Key_F2: + break; - case Qt::Key_Up: - break; + case Qt::Key_Up: + break; - case Qt::Key_Down: - break; + case Qt::Key_Down: + break; - case Qt::Key_Left: - break; + case Qt::Key_Left: + break; - case Qt::Key_Right: - break; + case Qt::Key_Right: + break; - case Qt::Key_PageUp: - break; + case Qt::Key_PageUp: + break; - case Qt::Key_PageDown: - break; + case Qt::Key_PageDown: + break; } } @@ -643,71 +643,71 @@ void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event) */ void OPMapGadgetWidget::updatePosition() { - double uav_latitude, uav_longitude, uav_altitude, uav_yaw; - double gps_latitude, gps_longitude, gps_altitude, gps_heading; + double uav_latitude, uav_longitude, uav_altitude, uav_yaw; + double gps_latitude, gps_longitude, gps_altitude, gps_heading; - internals::PointLatLng uav_pos; - internals::PointLatLng gps_pos; + internals::PointLatLng uav_pos; + internals::PointLatLng gps_pos; - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QMutexLocker locker(&m_map_mutex); -// Pip I'm sorry, I know this was here with a purpose vvv -// from Pip: let you off :) - //if (!telemetry_connected) - // return; + // Pip I'm sorry, I know this was here with a purpose vvv + // from Pip: let you off :) + //if (!telemetry_connected) + // return; - // ************* - // get the current UAV details + // ************* + // get the current UAV details // get current UAV position - if (!getUAVPosition(uav_latitude, uav_longitude, uav_altitude)) + if (!getUAVPosition(uav_latitude, uav_longitude, uav_altitude)) return; // get current UAV heading - uav_yaw = getUAV_Yaw(); + uav_yaw = getUAV_Yaw(); - uav_pos = internals::PointLatLng(uav_latitude, uav_longitude); + uav_pos = internals::PointLatLng(uav_latitude, uav_longitude); - // ************* - // get the current GPS details + // ************* + // get the current GPS details - // get current GPS position - if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude)) - return; + // get current GPS position + if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude)) + return; - // get current GPS heading -// gps_heading = getGPS_Heading(); - gps_heading = 0; + // get current GPS heading + // gps_heading = getGPS_Heading(); + gps_heading = 0; - gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); + gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); - // ************* - // display the UAV position + // ************* + // display the UAV position QString str = "lat: " + QString::number(uav_pos.Lat(), 'f', 7) + " lon: " + QString::number(uav_pos.Lng(), 'f', 7) + - " " + QString::number(uav_yaw, 'f', 1) + "deg" + - " " + QString::number(uav_altitude, 'f', 1) + "m"; -// " " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s"; + " " + QString::number(uav_yaw, 'f', 1) + "deg" + + " " + QString::number(uav_altitude, 'f', 1) + "m"; + // " " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s"; m_widget->labelUAVPos->setText(str); - // ************* - // set the UAV icon position on the map + // ************* + // set the UAV icon position on the map - m_map->UAV->SetUAVPos(uav_pos, uav_altitude); // set the maps UAV position -// qDebug()<<"UAVPOSITION"<UAV->SetUAVHeading(uav_yaw); // set the maps UAV heading + m_map->UAV->SetUAVPos(uav_pos, uav_altitude); // set the maps UAV position + // qDebug()<<"UAVPOSITION"<UAV->SetUAVHeading(uav_yaw); // set the maps UAV heading - // ************* - // set the GPS icon position on the map + // ************* + // set the GPS icon position on the map - m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position - m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading + m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position + m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading - // ************* + // ************* } /** @@ -716,8 +716,8 @@ void OPMapGadgetWidget::updatePosition() */ void OPMapGadgetWidget::updateMousePos() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QMutexLocker locker(&m_map_mutex); @@ -727,7 +727,7 @@ void OPMapGadgetWidget::updateMousePos() if (!m_map->contentsRect().contains(p)) return; // the mouse is not on the map -// internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position + // internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position QGraphicsItem *item = m_map->itemAt(p); @@ -740,14 +740,14 @@ void OPMapGadgetWidget::updateMousePos() // find out if we have a waypoint under the mouse cursor mapcontrol::WayPointItem *wp = qgraphicsitem_cast(item); - if (m_mouse_lat_lon == lat_lon) + if (m_mouse_lat_lon == lat_lon) return; // the mouse has not moved - m_mouse_lat_lon = lat_lon; // yes it has! + m_mouse_lat_lon = lat_lon; // yes it has! internals::PointLatLng home_lat_lon = m_map->Home->Coord(); - QString s = QString::number(m_mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_mouse_lat_lon.Lng(), 'f', 7); + QString s = QString::number(m_mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_mouse_lat_lon.Lng(), 'f', 7); if (wp) { s += " wp[" + QString::number(wp->Number()) + "]"; @@ -758,33 +758,33 @@ void OPMapGadgetWidget::updateMousePos() s += " " + QString::number(bear, 'f', 1) + "deg"; } else - if (home) - { - s += " home"; - - double dist = distance(home_lat_lon, m_mouse_lat_lon); - double bear = bearing(home_lat_lon, m_mouse_lat_lon); - s += " " + QString::number(dist * 1000, 'f', 1) + "m"; - s += " " + QString::number(bear, 'f', 1) + "deg"; - } - else - if (uav) - { - s += " uav"; - - double latitude; - double longitude; - double altitude; - if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position + if (home) { - internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); + s += " home"; -// double dist = distance(home_lat_lon, uav_pos); -// double bear = bearing(home_lat_lon, uav_pos); -// s += " " + QString::number(dist * 1000, 'f', 1) + "m"; -// s += " " + QString::number(bear, 'f', 1) + "deg"; + double dist = distance(home_lat_lon, m_mouse_lat_lon); + double bear = bearing(home_lat_lon, m_mouse_lat_lon); + s += " " + QString::number(dist * 1000, 'f', 1) + "m"; + s += " " + QString::number(bear, 'f', 1) + "deg"; } - } + else + if (uav) + { + s += " uav"; + + double latitude; + double longitude; + double altitude; + if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position + { + internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); + + // double dist = distance(home_lat_lon, uav_pos); + // double bear = bearing(home_lat_lon, uav_pos); + // s += " " + QString::number(dist * 1000, 'f', 1) + "m"; + // s += " " + QString::number(bear, 'f', 1) + "deg"; + } + } m_widget->labelMousePos->setText(s); } @@ -797,24 +797,24 @@ void OPMapGadgetWidget::updateMousePos() */ void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QString s = "tot:" + QString::number(zoomt, 'f', 1) + " rea:" + QString::number(zoom, 'f', 1) + " dig:" + QString::number(zoomd, 'f', 1); m_widget->labelMapZoom->setText(s); int i_zoom = (int)(zoomt + 0.5); - if (i_zoom < m_min_zoom) i_zoom = m_min_zoom; + if (i_zoom < m_min_zoom) i_zoom = m_min_zoom; else - if (i_zoom > m_max_zoom) i_zoom = m_max_zoom; + if (i_zoom > m_max_zoom) i_zoom = m_max_zoom; if (m_widget->horizontalSliderZoom->value() != i_zoom) - m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position + m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position - int index0_zoom = i_zoom - m_min_zoom; // zoom level starting at index level '0' + int index0_zoom = i_zoom - m_min_zoom; // zoom level starting at index level '0' if (index0_zoom < zoomAct.count()) - zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level + zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level } void OPMapGadgetWidget::OnMapDrag() @@ -823,8 +823,8 @@ void OPMapGadgetWidget::OnMapDrag() void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QString coord_str = QString::number(point.Lat(), 'f', 7) + " " + QString::number(point.Lng(), 'f', 7) + " "; m_widget->labelMapPos->setText(coord_str); @@ -835,20 +835,20 @@ void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) */ void OPMapGadgetWidget::OnTilesStillToLoad(int number) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; -// if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) -// m_widget->progressBarMap->setMaximum(number); + // if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) + // m_widget->progressBarMap->setMaximum(number); - if (m_widget->progressBarMap->maximum() < number) - m_widget->progressBarMap->setMaximum(number); + if (m_widget->progressBarMap->maximum() < number) + m_widget->progressBarMap->setMaximum(number); - m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar + m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar -// m_widget->labelNumTilesToLoad->setText(QString::number(number)); + // m_widget->labelNumTilesToLoad->setText(QString::number(number)); - m_prev_tile_number = number; + m_prev_tile_number = number; } /** @@ -856,8 +856,8 @@ void OPMapGadgetWidget::OnTilesStillToLoad(int number) */ void OPMapGadgetWidget::OnTileLoadStart() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_widget->progressBarMap->setVisible(true); } @@ -870,8 +870,8 @@ void OPMapGadgetWidget::OnTileLoadStart() void OPMapGadgetWidget::OnTileLoadComplete() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_widget->progressBarMap->setVisible(false); } @@ -900,38 +900,38 @@ void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumb void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) { -// qDebug("opmap: WPValuesChanged"); + // qDebug("opmap: WPValuesChanged"); switch (m_map_mode) { - case Normal_MapMode: - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { // search for the waypoint in our own waypoint list and update it - if (!wp) continue; - if (!wp->map_wp_item) continue; - if (wp->map_wp_item != waypoint) continue; - // found the waypoint in our list - wp->coord = waypoint->Coord(); - wp->altitude = waypoint->Altitude(); - wp->description = waypoint->Description(); - break; - } - m_waypoint_list_mutex.unlock(); + case Normal_MapMode: + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { // search for the waypoint in our own waypoint list and update it + if (!wp) continue; + if (!wp->map_wp_item) continue; + if (wp->map_wp_item != waypoint) continue; + // found the waypoint in our list + wp->coord = waypoint->Coord(); + wp->altitude = waypoint->Altitude(); + wp->description = waypoint->Description(); break; + } + m_waypoint_list_mutex.unlock(); + break; - case MagicWaypoint_MapMode: - // update our copy of the magic waypoint - if (m_magic_waypoint.map_wp_item && m_magic_waypoint.map_wp_item == waypoint) - { - m_magic_waypoint.coord = waypoint->Coord(); - m_magic_waypoint.altitude = waypoint->Altitude(); - m_magic_waypoint.description = waypoint->Description(); + case MagicWaypoint_MapMode: + // update our copy of the magic waypoint + if (m_magic_waypoint.map_wp_item && m_magic_waypoint.map_wp_item == waypoint) + { + m_magic_waypoint.coord = waypoint->Coord(); + m_magic_waypoint.altitude = waypoint->Altitude(); + m_magic_waypoint.description = waypoint->Description(); - // move the UAV to the magic waypoint position - // moveToMagicWaypointPosition(); - } - break; + // move the UAV to the magic waypoint position + // moveToMagicWaypointPosition(); + } + break; } } @@ -974,8 +974,8 @@ void OPMapGadgetWidget::on_toolButtonMapHome_clicked() void OPMapGadgetWidget::on_toolButtonMapUAV_clicked() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QMutexLocker locker(&m_map_mutex); @@ -984,16 +984,16 @@ void OPMapGadgetWidget::on_toolButtonMapUAV_clicked() void OPMapGadgetWidget::on_toolButtonMapUAVheading_clicked() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; followUAVheadingAct->toggle(); } void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; QMutexLocker locker(&m_map_mutex); @@ -1026,30 +1026,30 @@ void OPMapGadgetWidget::on_toolButtonMoveToWP_clicked() void OPMapGadgetWidget::onTelemetryConnect() { - m_telemetry_connected = true; + m_telemetry_connected = true; - if (!obum) return; + if (!obum) return; - bool set; - double LLA[3]; + bool set; + double LLA[3]; - // *********************** - // fetch the home location + // *********************** + // fetch the home location - if (obum->getHomeLocation(set, LLA) < 0) - return; // error + if (obum->getHomeLocation(set, LLA) < 0) + return; // error - setHome(internals::PointLatLng(LLA[0], LLA[1])); + setHome(internals::PointLatLng(LLA[0], LLA[1])); if (m_map) - m_map->SetCurrentPosition(m_home_position.coord); // set the map position + m_map->SetCurrentPosition(m_home_position.coord); // set the map position // *********************** } void OPMapGadgetWidget::onTelemetryDisconnect() { - m_telemetry_connected = false; + m_telemetry_connected = false; } // Updates the Home position icon whenever the HomePosition object is updated @@ -1071,21 +1071,21 @@ void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) */ void OPMapGadgetWidget::setHome(QPointF pos) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; double latitude = pos.x(); double longitude = pos.y(); if (latitude > 90) latitude = 90; else - if (latitude < -90) latitude = -90; + if (latitude < -90) latitude = -90; if (longitude != longitude) longitude = 0; // nan detection else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; setHome(internals::PointLatLng(latitude, longitude)); } @@ -1095,8 +1095,8 @@ void OPMapGadgetWidget::setHome(QPointF pos) */ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (pos_lat_lon.Lat() != pos_lat_lon.Lat() || pos_lat_lon.Lng() != pos_lat_lon.Lng()) return;; // nan prevention @@ -1106,21 +1106,21 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) if (latitude != latitude) latitude = 0; // nan detection else - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; if (longitude != longitude) longitude = 0; // nan detection else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; // ********* - m_home_position.coord = internals::PointLatLng(latitude, longitude); + m_home_position.coord = internals::PointLatLng(latitude, longitude); - m_map->Home->SetCoord(m_home_position.coord); + m_map->Home->SetCoord(m_home_position.coord); m_map->Home->RefreshPos(); // move the magic waypoint to keep it within the safe area boundry @@ -1133,74 +1133,74 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) */ void OPMapGadgetWidget::goHome() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; followUAVpositionAct->setChecked(false); - internals::PointLatLng home_pos = m_home_position.coord; // get the home location + internals::PointLatLng home_pos = m_home_position.coord; // get the home location m_map->SetCurrentPosition(home_pos); // center the map onto the home location } void OPMapGadgetWidget::zoomIn() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; int zoom = m_map->ZoomTotal() + 1; - if (zoom < m_min_zoom) zoom = m_min_zoom; + if (zoom < m_min_zoom) zoom = m_min_zoom; else - if (zoom > m_max_zoom) zoom = m_max_zoom; + if (zoom > m_max_zoom) zoom = m_max_zoom; m_map->SetZoom(zoom); } void OPMapGadgetWidget::zoomOut() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; int zoom = m_map->ZoomTotal() - 1; - if (zoom < m_min_zoom) zoom = m_min_zoom; + if (zoom < m_min_zoom) zoom = m_min_zoom; else - if (zoom > m_max_zoom) zoom = m_max_zoom; + if (zoom > m_max_zoom) zoom = m_max_zoom; m_map->SetZoom(zoom); } void OPMapGadgetWidget::setMaxUpdateRate(int update_rate) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; - int list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); - int min_rate = max_update_rate_list[0]; - int max_rate = max_update_rate_list[list_size - 1]; + int list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); + int min_rate = max_update_rate_list[0]; + int max_rate = max_update_rate_list[list_size - 1]; - if (update_rate < min_rate) update_rate = min_rate; - else - if (update_rate > max_rate) update_rate = max_rate; + if (update_rate < min_rate) update_rate = min_rate; + else + if (update_rate > max_rate) update_rate = max_rate; - m_maxUpdateRate = update_rate; + m_maxUpdateRate = update_rate; - if (m_updateTimer) - m_updateTimer->setInterval(m_maxUpdateRate); + if (m_updateTimer) + m_updateTimer->setInterval(m_maxUpdateRate); -// if (m_statusUpdateTimer) -// m_statusUpdateTimer->setInterval(m_maxUpdateRate); + // if (m_statusUpdateTimer) + // m_statusUpdateTimer->setInterval(m_maxUpdateRate); } void OPMapGadgetWidget::setZoom(int zoom) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; - if (zoom < m_min_zoom) zoom = m_min_zoom; + if (zoom < m_min_zoom) zoom = m_min_zoom; else - if (zoom > m_max_zoom) zoom = m_max_zoom; + if (zoom > m_max_zoom) zoom = m_max_zoom; internals::MouseWheelZoomType::Types zoom_type = m_map->GetMouseWheelZoomType(); m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::ViewCenter); @@ -1212,8 +1212,8 @@ void OPMapGadgetWidget::setZoom(int zoom) void OPMapGadgetWidget::setPosition(QPointF pos) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; double latitude = pos.y(); double longitude = pos.x(); @@ -1223,86 +1223,86 @@ void OPMapGadgetWidget::setPosition(QPointF pos) if (latitude > 90) latitude = 90; else - if (latitude < -90) latitude = -90; + if (latitude < -90) latitude = -90; if (longitude > 180) longitude = 180; else - if (longitude < -180) longitude = -180; + if (longitude < -180) longitude = -180; m_map->SetCurrentPosition(internals::PointLatLng(latitude, longitude)); } void OPMapGadgetWidget::setMapProvider(QString provider) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetMapType(mapcontrol::Helper::MapTypeFromString(provider)); } void OPMapGadgetWidget::setAccessMode(QString accessMode) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->configuration->SetAccessMode(mapcontrol::Helper::AccessModeFromString(accessMode)); } void OPMapGadgetWidget::setUseOpenGL(bool useOpenGL) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetUseOpenGL(useOpenGL); } void OPMapGadgetWidget::setShowTileGridLines(bool showTileGridLines) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetShowTileGridLines(showTileGridLines); } void OPMapGadgetWidget::setUseMemoryCache(bool useMemoryCache) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->configuration->SetUseMemoryCache(useMemoryCache); } void OPMapGadgetWidget::setCacheLocation(QString cacheLocation) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; cacheLocation = cacheLocation.simplified(); // remove any surrounding spaces if (cacheLocation.isEmpty()) return; -// #if defined(Q_WS_WIN) -// if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; -// #elif defined(Q_WS_X11) - if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #elif defined(Q_WS_MAC) -// if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #endif + // #if defined(Q_WS_WIN) + // if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; + // #elif defined(Q_WS_X11) + if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); + // #elif defined(Q_WS_MAC) + // if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); + // #endif QDir dir; if (!dir.exists(cacheLocation)) if (!dir.mkpath(cacheLocation)) return; -// qDebug() << "opmap: map cache dir: " << cacheLocation; + // qDebug() << "opmap: map cache dir: " << cacheLocation; m_map->configuration->SetCacheLocation(cacheLocation); } void OPMapGadgetWidget::setMapMode(opMapModeType mode) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (mode != Normal_MapMode && mode != MagicWaypoint_MapMode) mode = Normal_MapMode; // fix error @@ -1311,87 +1311,87 @@ void OPMapGadgetWidget::setMapMode(opMapModeType mode) { // no change in map mode switch (mode) { // make sure the UI buttons are set correctly - case Normal_MapMode: - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - break; - case MagicWaypoint_MapMode: - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - break; + case Normal_MapMode: + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + break; + case MagicWaypoint_MapMode: + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + break; } return; } switch (mode) { - case Normal_MapMode: - m_map_mode = Normal_MapMode; + case Normal_MapMode: + m_map_mode = Normal_MapMode; - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); + hideMagicWaypointControls(); - // delete the magic waypoint from the map - if (m_magic_waypoint.map_wp_item) - { - m_magic_waypoint.coord = m_magic_waypoint.map_wp_item->Coord(); - m_magic_waypoint.altitude = m_magic_waypoint.map_wp_item->Altitude(); - m_magic_waypoint.description = m_magic_waypoint.map_wp_item->Description(); - m_magic_waypoint.map_wp_item = NULL; - } - m_map->WPDeleteAll(); + // delete the magic waypoint from the map + if (m_magic_waypoint.map_wp_item) + { + m_magic_waypoint.coord = m_magic_waypoint.map_wp_item->Coord(); + m_magic_waypoint.altitude = m_magic_waypoint.map_wp_item->Altitude(); + m_magic_waypoint.description = m_magic_waypoint.map_wp_item->Description(); + m_magic_waypoint.map_wp_item = NULL; + } + m_map->WPDeleteAll(); - // restore the normal waypoints on the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - if (!wp->map_wp_item) continue; - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - m_waypoint_list_mutex.unlock(); + // restore the normal waypoints on the map + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); + if (!wp->map_wp_item) continue; + wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); + wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); + if (!wp->locked) + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + else + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + wp->map_wp_item->update(); + } + m_waypoint_list_mutex.unlock(); - break; + break; - case MagicWaypoint_MapMode: - m_map_mode = MagicWaypoint_MapMode; + case MagicWaypoint_MapMode: + m_map_mode = MagicWaypoint_MapMode; - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - showMagicWaypointControls(); + showMagicWaypointControls(); - // delete the normal waypoints from the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - if (!wp->map_wp_item) continue; - wp->coord = wp->map_wp_item->Coord(); - wp->altitude = wp->map_wp_item->Altitude(); - wp->description = wp->map_wp_item->Description(); - wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0; - wp->map_wp_item = NULL; - } - m_map->WPDeleteAll(); - m_waypoint_list_mutex.unlock(); + // delete the normal waypoints from the map + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + if (!wp->map_wp_item) continue; + wp->coord = wp->map_wp_item->Coord(); + wp->altitude = wp->map_wp_item->Altitude(); + wp->description = wp->map_wp_item->Description(); + wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0; + wp->map_wp_item = NULL; + } + m_map->WPDeleteAll(); + m_waypoint_list_mutex.unlock(); - // restore the magic waypoint on the map - m_magic_waypoint.map_wp_item = m_map->WPCreate(m_magic_waypoint.coord, m_magic_waypoint.altitude, m_magic_waypoint.description); - m_magic_waypoint.map_wp_item->setZValue(10 + m_magic_waypoint.map_wp_item->Number()); - m_magic_waypoint.map_wp_item->SetShowNumber(false); - m_magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + // restore the magic waypoint on the map + m_magic_waypoint.map_wp_item = m_map->WPCreate(m_magic_waypoint.coord, m_magic_waypoint.altitude, m_magic_waypoint.description); + m_magic_waypoint.map_wp_item->setZValue(10 + m_magic_waypoint.map_wp_item->Number()); + m_magic_waypoint.map_wp_item->SetShowNumber(false); + m_magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); - break; + break; } } @@ -1400,10 +1400,10 @@ void OPMapGadgetWidget::setMapMode(opMapModeType mode) void OPMapGadgetWidget::createActions() { - int list_size; + int list_size; - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; // *********************** // create menu actions @@ -1482,9 +1482,9 @@ void OPMapGadgetWidget::createActions() setHomeAct = new QAction(tr("Set the home location"), this); setHomeAct->setStatusTip(tr("Set the home location to where you clicked")); - #if !defined(allow_manual_home_location_move) - setHomeAct->setEnabled(false); - #endif +#if !defined(allow_manual_home_location_move) + setHomeAct->setEnabled(false); +#endif connect(setHomeAct, SIGNAL(triggered()), this, SLOT(onSetHomeAct_triggered())); goHomeAct = new QAction(tr("Go to &Home location"), this); @@ -1575,7 +1575,7 @@ void OPMapGadgetWidget::createActions() zoomActGroup = new QActionGroup(this); connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onZoomActGroup_triggered(QAction *))); zoomAct.clear(); - for (int i = m_min_zoom; i <= m_max_zoom; i++) + for (int i = m_min_zoom; i <= m_max_zoom; i++) { QAction *zoom_act = new QAction(QString::number(i), zoomActGroup); zoom_act->setCheckable(true); @@ -1583,22 +1583,22 @@ void OPMapGadgetWidget::createActions() zoomAct.append(zoom_act); } - maxUpdateRateActGroup = new QActionGroup(this); - connect(maxUpdateRateActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMaxUpdateRateActGroup_triggered(QAction *))); - maxUpdateRateAct.clear(); - list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); - for (int i = 0; i < list_size; i++) - { - QAction *maxUpdateRate_act; - int j = max_update_rate_list[i]; - maxUpdateRate_act = new QAction(QString::number(j), maxUpdateRateActGroup); - maxUpdateRate_act->setCheckable(true); - maxUpdateRate_act->setData(j); - maxUpdateRate_act->setChecked(j == m_maxUpdateRate); - maxUpdateRateAct.append(maxUpdateRate_act); - } + maxUpdateRateActGroup = new QActionGroup(this); + connect(maxUpdateRateActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMaxUpdateRateActGroup_triggered(QAction *))); + maxUpdateRateAct.clear(); + list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); + for (int i = 0; i < list_size; i++) + { + QAction *maxUpdateRate_act; + int j = max_update_rate_list[i]; + maxUpdateRate_act = new QAction(QString::number(j), maxUpdateRateActGroup); + maxUpdateRate_act->setCheckable(true); + maxUpdateRate_act->setData(j); + maxUpdateRate_act->setChecked(j == m_maxUpdateRate); + maxUpdateRateAct.append(maxUpdateRate_act); + } - // ***** + // ***** // safe area showSafeAreaAct = new QAction(tr("Show Safe Area"), this); @@ -1610,8 +1610,8 @@ void OPMapGadgetWidget::createActions() safeAreaActGroup = new QActionGroup(this); connect(safeAreaActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onSafeAreaActGroup_triggered(QAction *))); safeAreaAct.clear(); - list_size = sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0]); - for (int i = 0; i < list_size; i++) + list_size = sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0]); + for (int i = 0; i < list_size; i++) { int safeArea = safe_area_radius_list[i]; QAction *safeArea_act = new QAction(QString::number(safeArea) + "m", safeAreaActGroup); @@ -1657,8 +1657,8 @@ void OPMapGadgetWidget::createActions() uavTrailTimeActGroup = new QActionGroup(this); connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *))); uavTrailTimeAct.clear(); - list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); - for (int i = 0; i < list_size; i++) + list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); + for (int i = 0; i < list_size; i++) { int uav_trail_time = uav_trail_time_list[i]; QAction *uavTrailTime_act = new QAction(QString::number(uav_trail_time) + " sec", uavTrailTimeActGroup); @@ -1671,8 +1671,8 @@ void OPMapGadgetWidget::createActions() uavTrailDistanceActGroup = new QActionGroup(this); connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *))); uavTrailDistanceAct.clear(); - list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); - for (int i = 0; i < list_size; i++) + list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); + for (int i = 0; i < list_size; i++) { int uav_trail_distance = uav_trail_distance_list[i]; QAction *uavTrailDistance_act = new QAction(QString::number(uav_trail_distance) + " meters", uavTrailDistanceActGroup); @@ -1689,8 +1689,8 @@ void OPMapGadgetWidget::createActions() void OPMapGadgetWidget::onReloadAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->ReloadMap(); } @@ -1703,50 +1703,50 @@ void OPMapGadgetWidget::onRipAct_triggered() void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() { QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); } void OPMapGadgetWidget::onCopyMouseLatToClipAct_triggered() { QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard); } void OPMapGadgetWidget::onCopyMouseLonToClipAct_triggered() { QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); } void OPMapGadgetWidget::onShowCompassAct_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetShowCompass(show); } void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetShowDiagnostics(show); } void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->Home->setVisible(show); } void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->UAV->setVisible(show); m_map->GPS->setVisible(show); @@ -1754,8 +1754,8 @@ void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->UAV->SetShowTrail(show); m_map->GPS->SetShowTrail(show); @@ -1763,8 +1763,8 @@ void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->UAV->SetShowTrailLine(show); m_map->GPS->SetShowTrailLine(show); @@ -1792,55 +1792,55 @@ void OPMapGadgetWidget::onGoZoomOutAct_triggered() void OPMapGadgetWidget::onZoomActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) - return; + if (!m_widget || !m_map || !action) + return; setZoom(action->data().toInt()); } void OPMapGadgetWidget::onMaxUpdateRateActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) - return; + if (!m_widget || !m_map || !action) + return; - setMaxUpdateRate(action->data().toInt()); + setMaxUpdateRate(action->data().toInt()); } void OPMapGadgetWidget::onGoMouseClickAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position } void OPMapGadgetWidget::onSetHomeAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; - setHome(m_context_menu_lat_lon); + setHome(m_context_menu_lat_lon); setHomeLocationObject(); // update the HomeLocation UAVObject } void OPMapGadgetWidget::onGoHomeAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; goHome(); } void OPMapGadgetWidget::onGoUAVAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; double latitude; double longitude; double altitude; - if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position + if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position { internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position internals::PointLatLng map_pos = m_map->CurrentPosition(); // current MAP position @@ -1850,8 +1850,8 @@ void OPMapGadgetWidget::onGoUAVAct_triggered() void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_widget->toolButtonMapUAV->isChecked() != checked) m_widget->toolButtonMapUAV->setChecked(checked); @@ -1861,8 +1861,8 @@ void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked) void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_widget->toolButtonMapUAVheading->isChecked() != checked) m_widget->toolButtonMapUAVheading->setChecked(checked); @@ -1872,8 +1872,8 @@ void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) - return; + if (!m_widget || !m_map || !action) + return; int trail_type_idx = action->data().toInt(); @@ -1885,8 +1885,8 @@ void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) void OPMapGadgetWidget::onClearUAVtrailAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; m_map->UAV->DeleteTrail(); m_map->GPS->DeleteTrail(); @@ -1894,8 +1894,8 @@ void OPMapGadgetWidget::onClearUAVtrailAct_triggered() void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) - return; + if (!m_widget || !m_map || !action) + return; int trail_time = (double)action->data().toInt(); @@ -1904,8 +1904,8 @@ void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) - return; + if (!m_widget || !m_map || !action) + return; int trail_distance = action->data().toInt(); @@ -1918,15 +1918,15 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) /* void OPMapGadgetWidget::onAddWayPointAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_map_mode != Normal_MapMode) return; m_waypoint_list_mutex.lock(); - // create a waypoint on the map at the last known mouse position + // create a waypoint on the map at the last known mouse position t_waypoint *wp = new t_waypoint; wp->map_wp_item = NULL; wp->coord = context_menu_lat_lon; @@ -1966,8 +1966,8 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() /* void OPMapGadgetWidget::onEditWayPointAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_map_mode != Normal_MapMode) return; @@ -2078,7 +2078,7 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() QMutexLocker locker(&m_waypoint_list_mutex); - m_map->WPDeleteAll(); + m_map->WPDeleteAll(); foreach (t_waypoint *wp, m_waypoint_list) { @@ -2110,7 +2110,7 @@ void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show) void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action) { - if (!m_widget || !m_map || !action) + if (!m_widget || !m_map || !action) return; int radius = action->data().toInt(); @@ -2133,10 +2133,10 @@ void OPMapGadgetWidget::homeMagicWaypoint() if (m_map_mode != MagicWaypoint_MapMode) return; - m_magic_waypoint.coord = m_home_position.coord; + m_magic_waypoint.coord = m_home_position.coord; - if (m_magic_waypoint.map_wp_item) - m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); + if (m_magic_waypoint.map_wp_item) + m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); } // ************************************************************************************* @@ -2150,8 +2150,8 @@ void OPMapGadgetWidget::moveToMagicWaypointPosition() if (m_map_mode != MagicWaypoint_MapMode) return; -// internals::PointLatLng coord = magic_waypoint.coord; -// double altitude = magic_waypoint.altitude; + // internals::PointLatLng coord = magic_waypoint.coord; + // double altitude = magic_waypoint.altitude; // ToDo: @@ -2220,11 +2220,11 @@ void OPMapGadgetWidget::showMagicWaypointControls() m_widget->lineWaypoint->setVisible(true); m_widget->toolButtonHomeWaypoint->setVisible(true); - #if defined(allow_manual_home_location_move) - m_widget->toolButtonMoveToWP->setVisible(true); - #else - m_widget->toolButtonMoveToWP->setVisible(false); - #endif +#if defined(allow_manual_home_location_move) + m_widget->toolButtonMoveToWP->setVisible(true); +#else + m_widget->toolButtonMoveToWP->setVisible(false); +#endif } // ************************************************************************************* @@ -2234,25 +2234,25 @@ void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() { // calcute the bearing and distance from the home position to the magic waypoint - double dist = distance(m_home_position.coord, m_magic_waypoint.coord); - double bear = bearing(m_home_position.coord, m_magic_waypoint.coord); + double dist = distance(m_home_position.coord, m_magic_waypoint.coord); + double bear = bearing(m_home_position.coord, m_magic_waypoint.coord); // get the maximum safe distance - in kilometers double boundry_dist = (double)m_map->Home->SafeArea() / 1000; -// if (dist <= boundry_dist) -// return; // the magic waypoint is still within the safe area, don't move it + // if (dist <= boundry_dist) + // return; // the magic waypoint is still within the safe area, don't move it if (dist > boundry_dist) dist = boundry_dist; // move the magic waypoint - m_magic_waypoint.coord = destPoint(m_home_position.coord, bear, dist); + m_magic_waypoint.coord = destPoint(m_home_position.coord, bear, dist); if (m_map_mode == MagicWaypoint_MapMode) { // move the on-screen waypoint - if (m_magic_waypoint.map_wp_item) - m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); + if (m_magic_waypoint.map_wp_item) + m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); } } @@ -2269,7 +2269,7 @@ double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::Point // *********************** // Haversine formula -/* + /* double delta_lat = lat2 - lat1; double delta_lon = lon2 - lon1; @@ -2299,7 +2299,7 @@ double OPMapGadgetWidget::bearing(internals::PointLatLng from, internals::PointL double lat2 = to.Lat() * deg_to_rad; double lon2 = to.Lng() * deg_to_rad; -// double delta_lat = lat2 - lat1; + // double delta_lat = lat2 - lat1; double delta_lon = lon2 - lon1; double y = sin(delta_lon) * cos(lat2); @@ -2379,33 +2379,33 @@ bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, doub double OPMapGadgetWidget::getUAV_Yaw() { - if (!obm) - return 0; + if (!obm) + return 0; - UAVObject *obj = dynamic_cast(obm->getObject(QString("AttitudeActual"))); - double yaw = obj->getField(QString("Yaw"))->getDouble(); + UAVObject *obj = dynamic_cast(obm->getObject(QString("AttitudeActual"))); + double yaw = obj->getField(QString("Yaw"))->getDouble(); - if (yaw != yaw) yaw = 0; // nan detection + if (yaw != yaw) yaw = 0; // nan detection - while (yaw < 0) yaw += 360; - while (yaw >= 360) yaw -= 360; + while (yaw < 0) yaw += 360; + while (yaw >= 360) yaw -= 360; - return yaw; + return yaw; } bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude) { - double LLA[3]; + double LLA[3]; - if (!obum) - return false; + if (!obum) + return false; - if (obum->getGPSPosition(LLA) < 0) - return false; // error + if (obum->getGPSPosition(LLA) < 0) + return false; // error - latitude = LLA[0]; - longitude = LLA[1]; - altitude = LLA[2]; + latitude = LLA[0]; + longitude = LLA[1]; + altitude = LLA[2]; return true; } @@ -2423,18 +2423,18 @@ void OPMapGadgetWidget::setMapFollowingMode() m_map->SetRotate(0); // reset map rotation to 0deg } else - if (!followUAVheadingAct->isChecked()) - { - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); - m_map->SetRotate(0); // reset map rotation to 0deg - } - else - { - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode + if (!followUAVheadingAct->isChecked()) + { + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); + m_map->SetRotate(0); // reset map rotation to 0deg + } + else + { + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode - m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap); - } + m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap); + } } // ************************************************************************************* @@ -2442,11 +2442,11 @@ void OPMapGadgetWidget::setMapFollowingMode() bool OPMapGadgetWidget::setHomeLocationObject() { - if (!obum) - return false; + if (!obum) + return false; - double LLA[3] = {m_home_position.coord.Lat(), m_home_position.coord.Lng(), m_home_position.altitude}; - return (obum->setHomeLocation(LLA, true) >= 0); + double LLA[3] = {m_home_position.coord.Lat(), m_home_position.coord.Lng(), m_home_position.altitude}; + return (obum->setHomeLocation(LLA, true) >= 0); } // ************************************************************************************* From 252f61bb8eac1aeab350f686bfa581b30cadb246 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 11 May 2012 19:31:01 -0500 Subject: [PATCH 005/508] A bit of preliminary cleanup and removing unused code to map gadget --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 59 ++++--------------- 1 file changed, 12 insertions(+), 47 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8cb4670f4..d1e778267 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -282,26 +282,19 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) // ************** // connect to the UAVObject updates we require to become a bit aware of our environment: - if (pm) - { - // Register for Home Location state changes - if (obm) - { - UAVDataObject *obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); - if (obj) - { - connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); - } - } + Q_ASSERT(pm); + Q_ASSERT(obm); - // Listen to telemetry connection events - TelemetryManager *telMngr = pm->getObject(); - if (telMngr) - { - connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); - } - } + // Register for Home Location state changes + HomeLocation *obj = HomeLocation::GetInstance(obm); + Q_ASSERT(obj != NULL); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); + + // Listen to telemetry connection events + TelemetryManager *telMngr = pm->getObject(); + Q_ASSERT(telMngr); + connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); // ************** // create the desired timers @@ -332,29 +325,6 @@ OPMapGadgetWidget::~OPMapGadgetWidget() m_map->SetShowUAV(false); // " " } - - // this destructor doesn't appear to be called at shutdown??? - - // #if defined(Q_OS_MAC) - // #elif defined(Q_OS_WIN) - // saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); - // #else - // #endif - - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - - - // todo: - - - delete wp->map_wp_item; - } - m_waypoint_list_mutex.unlock(); - m_waypoint_list.clear(); - if (m_map) { delete m_map; @@ -472,11 +442,6 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); - /* - menu.addAction(findPlaceAct); - - menu.addSeparator(); - */ QMenu safeArea("Safety Area definitions"); // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); From 7c8cc94f5e5b0428547337918b2948f1032d8e48 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 30 May 2012 08:07:01 -0500 Subject: [PATCH 006/508] In the revo bootloader check that the BOR bits are set to 2.7 volt threshold. This addresses an issue where a slow power ramp (e.g. some BEC) will stop it booting. --- flight/Bootloaders/Revolution/main.c | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/flight/Bootloaders/Revolution/main.c b/flight/Bootloaders/Revolution/main.c index b64ebc96a..4a944e7ac 100644 --- a/flight/Bootloaders/Revolution/main.c +++ b/flight/Bootloaders/Revolution/main.c @@ -37,6 +37,7 @@ /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void FLASH_Download(); +void check_bor(); #define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) /* Private typedef -----------------------------------------------------------*/ @@ -75,6 +76,10 @@ int main() { PIOS_Board_Init(); PIOS_IAP_Init(); + // Make sure the brown out reset value for this chip + // is 2.7 volts + check_bor(); + USB_connected = PIOS_USB_CheckAvailable(0); if (PIOS_IAP_CheckRequest() == true) { @@ -206,3 +211,19 @@ uint8_t processRX() { return true; } +/** + * Check the brown out reset threshold is 2.7 volts and if not + * resets it. This solves an issue that can prevent boards + * powering up with some BEC + */ +void check_bor() +{ + uint8_t bor = FLASH_OB_GetBOR(); + if(bor != OB_BOR_LEVEL3) { + FLASH_OB_Unlock(); + FLASH_OB_BORConfig(OB_BOR_LEVEL3); + FLASH_OB_Lock(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + } +} + From c76c71cfcedfd0201254c4893d2acc0dfed909c1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 30 May 2012 09:50:05 -0500 Subject: [PATCH 007/508] No reason to init the board a second time --- flight/Bootloaders/Revolution/main.c | 1 - 1 file changed, 1 deletion(-) diff --git a/flight/Bootloaders/Revolution/main.c b/flight/Bootloaders/Revolution/main.c index 4a944e7ac..9084df31b 100644 --- a/flight/Bootloaders/Revolution/main.c +++ b/flight/Bootloaders/Revolution/main.c @@ -91,7 +91,6 @@ int main() { GO_dfu = (USB_connected == true) || (User_DFU_request == true); if (GO_dfu == true) { - PIOS_Board_Init(); if (User_DFU_request == true) DeviceState = DFUidle; else From ed2b9f1f63fcf9d8b6289ef8df6cef533f106171 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 30 May 2012 10:12:40 -0500 Subject: [PATCH 008/508] Make PIOS_LED init it's GPIO clocks so it doesn't rely on startup code --- flight/PiOS/STM32F4xx/pios_led.c | 34 ++++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/flight/PiOS/STM32F4xx/pios_led.c b/flight/PiOS/STM32F4xx/pios_led.c index c73d37198..949ad3717 100644 --- a/flight/PiOS/STM32F4xx/pios_led.c +++ b/flight/PiOS/STM32F4xx/pios_led.c @@ -50,6 +50,40 @@ int32_t PIOS_LED_Init(const struct pios_led_cfg * cfg) for (uint8_t i = 0; i < cfg->num_leds; i++) { const struct pios_led * led = &(cfg->leds[i]); + /* Enable the peripheral clock for the GPIO */ + switch ((uint32_t)led->pin.gpio) { + case (uint32_t) GPIOA: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE); + break; + case (uint32_t) GPIOB: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE); + break; + case (uint32_t) GPIOC: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE); + break; + case (uint32_t) GPIOD: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE); + break; + case (uint32_t) GPIOE: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOE, ENABLE); + break; + case (uint32_t) GPIOF: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOF, ENABLE); + break; + case (uint32_t) GPIOG: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOG, ENABLE); + break; + case (uint32_t) GPIOH: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOH, ENABLE); + break; + case (uint32_t) GPIOI: + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOI, ENABLE); + break; + default: + PIOS_Assert(0); + break; + } + if (led->remap) { GPIO_PinAFConfig(led->pin.gpio, led->pin.init.GPIO_Pin, led->remap); } From f3e3a2f16ba233da46a86ca7cb412c90780e9dcf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 11 May 2012 20:29:53 -0500 Subject: [PATCH 009/508] Enable waypoints on the map again --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 128 +++++++++--------- .../src/plugins/opmap/opmapgadgetwidget.h | 86 ++++++------ 2 files changed, 103 insertions(+), 111 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index d1e778267..cda08c258 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -325,6 +325,21 @@ OPMapGadgetWidget::~OPMapGadgetWidget() m_map->SetShowUAV(false); // " " } + + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + + + // todo: + + + delete wp->map_wp_item; + } + m_waypoint_list_mutex.unlock(); + m_waypoint_list.clear(); + if (m_map) { delete m_map; @@ -442,6 +457,11 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); + /* + menu.addAction(findPlaceAct); + + menu.addSeparator(); + */ QMenu safeArea("Safety Area definitions"); // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); @@ -514,32 +534,32 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) // ********* + qDebug() << "Testing mode"; switch (m_map_mode) { case Normal_MapMode: + qDebug() << "Normal mode"; // only show the waypoint stuff if not in 'magic waypoint' mode - /* - menu.addSeparator()->setText(tr("Waypoints")); + menu.addSeparator()->setText(tr("Waypoints")); - menu.addAction(wayPointEditorAct); - menu.addAction(addWayPointAct); + menu.addAction(wayPointEditorAct); + menu.addAction(addWayPointAct); - if (m_mouse_waypoint) - { // we have a waypoint under the mouse - menu.addAction(editWayPointAct); + if (m_mouse_waypoint) + { // we have a waypoint under the mouse + menu.addAction(editWayPointAct); - lockWayPointAct->setChecked(waypoint_locked); - menu.addAction(lockWayPointAct); + lockWayPointAct->setChecked(waypoint_locked); + menu.addAction(lockWayPointAct); - if (!waypoint_locked) - menu.addAction(deleteWayPointAct); - } + if (!waypoint_locked) + menu.addAction(deleteWayPointAct); + } - m_waypoint_list_mutex.lock(); - if (m_waypoint_list.count() > 0) - menu.addAction(clearWayPointsAct); // we have waypoints - m_waypoint_list_mutex.unlock(); - */ + m_waypoint_list_mutex.lock(); + if (m_waypoint_list.count() > 0) + menu.addAction(clearWayPointsAct); // we have waypoints + m_waypoint_list_mutex.unlock(); break; @@ -1476,16 +1496,12 @@ void OPMapGadgetWidget::createActions() followUAVheadingAct->setChecked(false); connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); - /* - TODO: Waypoint support is disabled for v1.0 - */ - - /* + /* Waypoint stuff */ wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); wayPointEditorAct->setShortcut(tr("Ctrl+W")); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); wayPointEditorAct->setEnabled(false); // temporary - connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); + //connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); addWayPointAct = new QAction(tr("&Add waypoint"), this); addWayPointAct->setShortcut(tr("Ctrl+A")); @@ -1512,7 +1528,6 @@ void OPMapGadgetWidget::createActions() clearWayPointsAct->setShortcut(tr("Ctrl+C")); clearWayPointsAct->setStatusTip(tr("Clear waypoints")); connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); - */ homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position")); @@ -1877,24 +1892,20 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) m_map->UAV->SetTrailDistance(trail_distance); } -/** - * TODO: unused for v1.0 - **/ -/* void OPMapGadgetWidget::onAddWayPointAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_map_mode != Normal_MapMode) return; m_waypoint_list_mutex.lock(); - // create a waypoint on the map at the last known mouse position + // create a waypoint on the map at the last known mouse position t_waypoint *wp = new t_waypoint; wp->map_wp_item = NULL; - wp->coord = context_menu_lat_lon; + wp->coord = m_context_menu_lat_lon; wp->altitude = 0; wp->description = ""; wp->locked = false; @@ -1920,7 +1931,6 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() m_waypoint_list_mutex.unlock(); } -*/ /** * Called when the user asks to edit a waypoint from the map @@ -1928,11 +1938,10 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() * TODO: should open an interface to edit waypoint properties, or * propagate the signal to a specific WP plugin (tbd). **/ -/* void OPMapGadgetWidget::onEditWayPointAct_triggered() { - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (m_map_mode != Normal_MapMode) return; @@ -1944,12 +1953,7 @@ void OPMapGadgetWidget::onEditWayPointAct_triggered() m_mouse_waypoint = NULL; } -*/ -/** - * TODO: unused for v1.0 - */ -/* void OPMapGadgetWidget::onLockWayPointAct_triggered() { if (!m_widget || !m_map || !m_mouse_waypoint) @@ -1969,12 +1973,7 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() m_mouse_waypoint = NULL; } -*/ -/** - * TODO: unused for v1.0 - */ -/* void OPMapGadgetWidget::onDeleteWayPointAct_triggered() { if (!m_widget || !m_map) @@ -2008,31 +2007,29 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() break; } -// -// foreach (t_waypoint *wp, m_waypoint_list) -// { -// if (!wp) continue; -// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; -// -// // delete the waypoint from the map -// m_map->WPDelete(wp->map_wp_item); -// -// // delete the waypoint from our local waypoint list -// m_waypoint_list.removeOne(wp); -// -// delete wp; -// -// break; -// } + + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; + + // delete the waypoint from the map + m_map->WPDelete(wp->map_wp_item); + + // delete the waypoint from our local waypoint list + m_waypoint_list.removeOne(wp); + + delete wp; + + break; + } m_mouse_waypoint = NULL; } -*/ /** * TODO: No Waypoint support in v1.0 */ -/* void OPMapGadgetWidget::onClearWayPointsAct_triggered() { if (!m_widget || !m_map) @@ -2043,7 +2040,7 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() QMutexLocker locker(&m_waypoint_list_mutex); - m_map->WPDeleteAll(); + m_map->WPDeleteAll(); foreach (t_waypoint *wp, m_waypoint_list) { @@ -2056,7 +2053,6 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() m_waypoint_list.clear(); } -*/ void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() { diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 8d374acdc..b5728a79b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -7,7 +7,7 @@ * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin * @{ - * @brief The OpenPilot Map plugin + * @brief The OpenPilot Map plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -57,7 +57,7 @@ namespace Ui { - class OPMap_Widget; +class OPMap_Widget; } using namespace mapcontrol; @@ -96,7 +96,7 @@ class OPMapGadgetWidget : public QWidget public: OPMapGadgetWidget(QWidget *parent = 0); - ~OPMapGadgetWidget(); + ~OPMapGadgetWidget(); /** * @brief public functions @@ -115,8 +115,8 @@ public: void setUseMemoryCache(bool useMemoryCache); void setCacheLocation(QString cacheLocation); void setMapMode(opMapModeType mode); - void SetUavPic(QString UAVPic); - void setMaxUpdateRate(int update_rate); + void SetUavPic(QString UAVPic); + void setMaxUpdateRate(int update_rate); public slots: void homePositionUpdated(UAVObject *); @@ -142,21 +142,21 @@ private slots: * * Some are currently disabled for the v1.0 plugin version. */ -// void comboBoxFindPlace_returnPressed(); -// void on_toolButtonFindPlace_clicked(); + // void comboBoxFindPlace_returnPressed(); + // void on_toolButtonFindPlace_clicked(); void on_toolButtonZoomM_clicked(); void on_toolButtonZoomP_clicked(); void on_toolButtonMapHome_clicked(); void on_toolButtonMapUAV_clicked(); void on_toolButtonMapUAVheading_clicked(); void on_horizontalSliderZoom_sliderMoved(int position); -// void on_toolButtonAddWaypoint_clicked(); -// void on_treeViewWaypoints_clicked(QModelIndex index); -// void on_toolButtonHome_clicked(); -// void on_toolButtonNextWaypoint_clicked(); -// void on_toolButtonPrevWaypoint_clicked(); -// void on_toolButtonHoldPosition_clicked(); -// void on_toolButtonGo_clicked(); + // void on_toolButtonAddWaypoint_clicked(); + // void on_treeViewWaypoints_clicked(QModelIndex index); + // void on_toolButtonHome_clicked(); + // void on_toolButtonNextWaypoint_clicked(); + // void on_toolButtonPrevWaypoint_clicked(); + // void on_toolButtonHoldPosition_clicked(); + // void on_toolButtonGo_clicked(); void on_toolButtonMagicWaypointMapMode_clicked(); void on_toolButtonNormalMapMode_clicked(); void on_toolButtonHomeWaypoint_clicked(); @@ -191,7 +191,7 @@ private slots: void onCopyMouseLatLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLonToClipAct_triggered(); -// void onFindPlaceAct_triggered(); + // void onFindPlaceAct_triggered(); void onShowCompassAct_toggled(bool show); void onShowDiagnostics_toggled(bool show); void onShowUAVAct_toggled(bool show); @@ -206,14 +206,12 @@ private slots: void onGoUAVAct_triggered(); void onFollowUAVpositionAct_toggled(bool checked); void onFollowUAVheadingAct_toggled(bool checked); -/* - void onOpenWayPointEditorAct_triggered(); + //void onOpenWayPointEditorAct_triggered(); void onAddWayPointAct_triggered(); void onEditWayPointAct_triggered(); void onLockWayPointAct_triggered(); void onDeleteWayPointAct_triggered(); void onClearWayPointsAct_triggered(); -*/ void onMapModeActGroup_triggered(QAction *action); void onZoomActGroup_triggered(QAction *action); void onHomeMagicWaypointAct_triggered(); @@ -223,31 +221,31 @@ private slots: void onClearUAVtrailAct_triggered(); void onUAVTrailTimeActGroup_triggered(QAction *action); void onUAVTrailDistanceActGroup_triggered(QAction *action); - void onMaxUpdateRateActGroup_triggered(QAction *action); + void onMaxUpdateRateActGroup_triggered(QAction *action); private: - // ***** + // ***** - int m_min_zoom; - int m_max_zoom; + int m_min_zoom; + int m_max_zoom; double m_heading; // uav heading - internals::PointLatLng m_mouse_lat_lon; - internals::PointLatLng m_context_menu_lat_lon; + internals::PointLatLng m_mouse_lat_lon; + internals::PointLatLng m_context_menu_lat_lon; - int m_prev_tile_number; + int m_prev_tile_number; opMapModeType m_map_mode; - int m_maxUpdateRate; + int m_maxUpdateRate; - t_home m_home_position; + t_home m_home_position; - t_waypoint m_magic_waypoint; + t_waypoint m_magic_waypoint; - QStringList findPlaceWordList; + QStringList findPlaceWordList; QCompleter *findPlaceCompleter; QTimer *m_updateTimer; @@ -257,11 +255,11 @@ private: mapcontrol::OPMapWidget *m_map; - ExtensionSystem::PluginManager *pm; - UAVObjectManager *obm; - UAVObjectUtilManager *obum; + ExtensionSystem::PluginManager *pm; + UAVObjectManager *obm; + UAVObjectUtilManager *obum; - //opmap_waypointeditor_dialog waypoint_editor_dialog; + //opmap_waypointeditor_dialog waypoint_editor_dialog; //opmap_edit_waypoint_dialog waypoint_edit_dialog; @@ -274,9 +272,9 @@ private: QMutex m_map_mutex; - bool m_telemetry_connected; + bool m_telemetry_connected; - // ***** + // ***** void createActions(); @@ -284,7 +282,7 @@ private: QAction *closeAct2; QAction *reloadAct; QAction *ripAct; - QAction *copyMouseLatLonToClipAct; + QAction *copyMouseLatLonToClipAct; QAction *copyMouseLatToClipAct; QAction *copyMouseLonToClipAct; QAction *findPlaceAct; @@ -300,14 +298,12 @@ private: QAction *goUAVAct; QAction *followUAVpositionAct; QAction *followUAVheadingAct; - /* QAction *wayPointEditorAct; QAction *addWayPointAct; QAction *editWayPointAct; QAction *lockWayPointAct; QAction *deleteWayPointAct; QAction *clearWayPointsAct; - */ QAction *homeMagicWaypointAct; QAction *showSafeAreaAct; @@ -330,12 +326,12 @@ private: QActionGroup *zoomActGroup; QList zoomAct; - QActionGroup *maxUpdateRateActGroup; - QList maxUpdateRateAct; + QActionGroup *maxUpdateRateActGroup; + QList maxUpdateRateAct; - // ***** + // ***** - void homeMagicWaypoint(); + void homeMagicWaypoint(); void moveToMagicWaypointPosition(); @@ -351,13 +347,13 @@ private: double bearing(internals::PointLatLng from, internals::PointLatLng to); internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist); - bool getUAVPosition(double &latitude, double &longitude, double &altitude); - bool getGPSPosition(double &latitude, double &longitude, double &altitude); + bool getUAVPosition(double &latitude, double &longitude, double &altitude); + bool getGPSPosition(double &latitude, double &longitude, double &altitude); double getUAV_Yaw(); void setMapFollowingMode(); - bool setHomeLocationObject(); + bool setHomeLocationObject(); }; #endif /* OPMAP_GADGETWIDGET_H_ */ From 0f526fe67e6335b3d8b72f8aeced509d61a8bc1e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 11 May 2012 21:35:53 -0500 Subject: [PATCH 010/508] Initial commit of pathcompiler stub --- .../openpilotgcs/src/plugins/opmap/opmap.pro | 96 +++++++++--------- .../src/plugins/opmap/pathcompiler.cpp | 32 ++++++ .../src/plugins/opmap/pathcompiler.h | 97 +++++++++++++++++++ 3 files changed, 179 insertions(+), 46 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathcompiler.h diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index 5bb709d01..042b35d8e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -1,46 +1,50 @@ -TEMPLATE = lib -TARGET = OPMapGadget - -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(../../libs/opmapcontrol/opmapcontrol.pri) -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/uavobjectutil/uavobjectutil.pri) -include(../../plugins/uavtalk/uavtalk.pri) -include(../../libs/utils/utils.pri) - -HEADERS += opmapplugin.h \ - opmapgadgetoptionspage.h \ - opmapgadgetfactory.h \ - opmapgadgetconfiguration.h \ - opmapgadget.h \ - opmapgadgetwidget.h \ -# opmap_waypointeditor_dialog.h \ -# opmap_edit_waypoint_dialog.h \ - opmap_zoom_slider_widget.h \ - opmap_statusbar_widget.h \ - opmap_overlay_widget.h - -SOURCES += opmapplugin.cpp \ - opmapgadgetwidget.cpp \ - opmapgadgetoptionspage.cpp \ - opmapgadgetfactory.cpp \ - opmapgadgetconfiguration.cpp \ - opmapgadget.cpp \ - # opmap_waypointeditor_dialog.cpp \ - # opmap_edit_waypoint_dialog.cpp \ - opmap_zoom_slider_widget.cpp \ - opmap_statusbar_widget.cpp \ - opmap_overlay_widget.cpp - -OTHER_FILES += OPMapGadget.pluginspec - -FORMS += opmapgadgetoptionspage.ui \ - opmap_widget.ui \ - # opmap_waypointeditor_dialog.ui \ - # opmap_edit_waypoint_dialog.ui \ - opmap_zoom_slider_widget.ui \ - opmap_statusbar_widget.ui \ - opmap_overlay_widget.ui - -RESOURCES += opmap.qrc +TEMPLATE = lib +TARGET = OPMapGadget + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../libs/opmapcontrol/opmapcontrol.pri) +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) +include(../../plugins/uavtalk/uavtalk.pri) +include(../../libs/utils/utils.pri) + +HEADERS += opmapplugin.h \ + opmapgadgetoptionspage.h \ + opmapgadgetfactory.h \ + opmapgadgetconfiguration.h \ + opmapgadget.h \ + opmapgadgetwidget.h \ +# opmap_waypointeditor_dialog.h \ +# opmap_edit_waypoint_dialog.h \ + opmap_zoom_slider_widget.h \ + opmap_statusbar_widget.h \ + opmap_overlay_widget.h \ + pathcompiler.h + +SOURCES += opmapplugin.cpp \ + opmapgadgetwidget.cpp \ + opmapgadgetoptionspage.cpp \ + opmapgadgetfactory.cpp \ + opmapgadgetconfiguration.cpp \ + opmapgadget.cpp \ + # opmap_waypointeditor_dialog.cpp \ + # opmap_edit_waypoint_dialog.cpp \ + opmap_zoom_slider_widget.cpp \ + opmap_statusbar_widget.cpp \ + opmap_overlay_widget.cpp \ + pathcompiler.cpp + +OTHER_FILES += OPMapGadget.pluginspec + +FORMS += opmapgadgetoptionspage.ui \ + opmap_widget.ui \ + # opmap_waypointeditor_dialog.ui \ + # opmap_edit_waypoint_dialog.ui \ + opmap_zoom_slider_widget.ui \ + opmap_statusbar_widget.ui \ + opmap_overlay_widget.ui + +RESOURCES += opmap.qrc + + diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp new file mode 100644 index 000000000..2862b4695 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -0,0 +1,32 @@ +/** + ****************************************************************************** + * + * @file pathcompiler.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "pathcompiler.h" + +PathCompiler::PathCompiler(QObject *parent) : + QObject(parent) +{ +} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h new file mode 100644 index 000000000..565986fa3 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -0,0 +1,97 @@ +/** + ****************************************************************************** + * + * @file pathcompiler.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef PATHCOMPILER_H +#define PATHCOMPILER_H + +#include +#include + +/** + * This class is a two way adapter between a visualization of a path and the + * UAVObject representation on the flight controller. It also can support multiple + * ways of converting a path from what the user clicked to the underlying representation + * to achieve the desired end flight trajectory + */ +class PathCompiler : public QObject +{ + Q_OBJECT +public: + explicit PathCompiler(QObject *parent = 0); + + //! This method opens a dialog (if filename is null) and saves the path + int savePath(QString filename = null); + + //! This method opens a dialog (if filename is null) and loads the path + int loadPath(QString filename = null); + + //! Waypoint representation that is exchanged between visualization + struct waypoint { + float latitude; + float longitude; + }; + +signals: + /** + * Indicates something changed the waypoints and the map should + * update the display + */ + void visualizationChanged(QList); + +public slots: + /** + * These are slots that the visualization can call to manipulate the path. + * It is an important design detail that the visualiation _not_ attempt to maintain + * the list of waypoints itself. This starts the slippery of moving the path logic + * into the view. + */ + + /** + * add a waypoint + * @param waypoint the new waypoint to add + * @param position which position to insert it to, defaults to end + */ + void doAddWaypoint(struct PathCompiler::waypoint, int position = -1); + + /** + * Delete a waypoint + * @param index which waypoint to delete + */ + void doDelWaypoint(int index); + +public slots: + /** + * These are slots that the UAV can call to update the path. + */ + + /** + * When the UAV waypoints change trigger the pathcompiler to + * get the latest version and then update the visualization + */ + void doUpdateFromUAV(); +}; + +#endif // PATHCOMPILER_H From 6f6fdbe3e48498b88792d01962d2bf361aa323e1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 11 May 2012 22:35:17 -0500 Subject: [PATCH 011/508] Finish stubbing out the path compiler class. --- .../src/plugins/opmap/pathcompiler.cpp | 81 +++++++++++++++++++ .../src/plugins/opmap/pathcompiler.h | 11 +++ 2 files changed, 92 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 2862b4695..77460f74e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -25,8 +25,89 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "pathcompiler.h" +#include "uavobjectmanager.h" +#include "waypoint.h" +#include "homelocation.h" PathCompiler::PathCompiler(QObject *parent) : QObject(parent) { + Waypoint *waypoint = NULL; + HomeLocation *homeLocation = NULL; + + /* Connect the object updates */ + waypoint = Waypoint::GetInstance(getObjectManger()); + Q_ASSERT(waypoint); + if(waypoint) + connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV())); + + homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(homeLocation); + if(homeLocation) + connect(homeLocation, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV())); +} + +/** + * Helper method to get the uavobjectamanger + */ +UAVObjectManager * PathCompiler::getObjectManager() +{ + ExtensionSystem::PluginManager *pm = NULL; + UAVObjectUtilManager *objMngr = NULL; + + pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + if(pm) + objMngr = pm->getObject(); + Q_ASSERT(objMngr); + + return objMngr; +} + +/** + * This method opens a dialog (if filename is null) and saves the path + * @param filename The file to save the path to + * @returns -1 for failure, 0 for success + */ +int PathCompiler::savePath(QString filename = null) +{ + return -1; +} + +/** + * This method opens a dialog (if filename is null) and loads the path + * @param filename The file to load from + * @returns -1 for failure, 0 for success + */ +int PathCompiler::loadPath(QString filename = null) +{ + return -1; +} + +/** + * add a waypoint + * @param waypoint the new waypoint to add + * @param position which position to insert it to, defaults to end + */ +void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint, int position = -1) +{ + emit visualizationChanged(waypoints); +} + +/** + * Delete a waypoint + * @param index which waypoint to delete + */ +void PathCompiler::doDelWaypoint(int index) +{ + emit visualizationChanged(waypoints); +} + +/** + * When the UAV waypoints change trigger the pathcompiler to + * get the latest version and then update the visualization + */ +void PathCompiler::doUpdateFromUAV() +{ + emit visualizationChanged(waypoints); } diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 565986fa3..f0e71aae4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -29,6 +29,10 @@ #include #include +#include + +// TODO: Make this a singleton class and separate from map library. Not sure of the proper design pattern in Qt. +// factory? static variables? /** * This class is a two way adapter between a visualization of a path and the @@ -54,6 +58,13 @@ public: float longitude; }; +private: + //! Helper method to get uavobject manager + UAVObjectManager * getObjectManager(); + + //! The internal list of waypoints + QList waypoints; + signals: /** * Indicates something changed the waypoints and the map should From e348a1a582142fa8898c7c8c3018926cab4f55d0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 12:18:43 -0500 Subject: [PATCH 012/508] Get the waypoints from UAVO, format them into LLA and emit the signal --- .../src/plugins/opmap/pathcompiler.cpp | 102 +++++++++++++++--- .../src/plugins/opmap/pathcompiler.h | 16 +-- 2 files changed, 99 insertions(+), 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 77460f74e..640c75ade 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -24,10 +24,12 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "pathcompiler.h" -#include "uavobjectmanager.h" -#include "waypoint.h" -#include "homelocation.h" +#include +#include +#include +#include +#include +#include PathCompiler::PathCompiler(QObject *parent) : QObject(parent) @@ -36,7 +38,7 @@ PathCompiler::PathCompiler(QObject *parent) : HomeLocation *homeLocation = NULL; /* Connect the object updates */ - waypoint = Waypoint::GetInstance(getObjectManger()); + waypoint = Waypoint::GetInstance(getObjectManager()); Q_ASSERT(waypoint); if(waypoint) connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV())); @@ -53,12 +55,12 @@ PathCompiler::PathCompiler(QObject *parent) : UAVObjectManager * PathCompiler::getObjectManager() { ExtensionSystem::PluginManager *pm = NULL; - UAVObjectUtilManager *objMngr = NULL; + UAVObjectManager *objMngr = NULL; pm = ExtensionSystem::PluginManager::instance(); Q_ASSERT(pm); if(pm) - objMngr = pm->getObject(); + objMngr = pm->getObject(); Q_ASSERT(objMngr); return objMngr; @@ -69,8 +71,9 @@ UAVObjectManager * PathCompiler::getObjectManager() * @param filename The file to save the path to * @returns -1 for failure, 0 for success */ -int PathCompiler::savePath(QString filename = null) +int PathCompiler::savePath(QString filename) { + Q_UNUSED(filename); return -1; } @@ -79,8 +82,9 @@ int PathCompiler::savePath(QString filename = null) * @param filename The file to load from * @returns -1 for failure, 0 for success */ -int PathCompiler::loadPath(QString filename = null) +int PathCompiler::loadPath(QString filename) { + Q_UNUSED(filename); return -1; } @@ -89,18 +93,24 @@ int PathCompiler::loadPath(QString filename = null) * @param waypoint the new waypoint to add * @param position which position to insert it to, defaults to end */ -void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint, int position = -1) +void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint, int /* position */) { - emit visualizationChanged(waypoints); + } /** * Delete a waypoint * @param index which waypoint to delete */ -void PathCompiler::doDelWaypoint(int index) +void PathCompiler::doDelWaypoint(int /*index*/) { - emit visualizationChanged(waypoints); + // This method is awkward because there is no support + // on the FC for actually deleting a waypoint. We need + // to shift them all by one and set the new "last" waypoint + // to a stop action + + // Not implemented yet + Q_ASSERT(false); } /** @@ -109,5 +119,71 @@ void PathCompiler::doDelWaypoint(int index) */ void PathCompiler::doUpdateFromUAV() { + UAVObjectManager *objManager = getObjectManager(); + if (!objManager) + return; + + Waypoint *waypointObj = Waypoint::GetInstance(getObjectManager()); + Q_ASSERT(waypointObj); + if (waypointObj == NULL) + return; + + /* Get all the waypoints from the UAVO and create a representation for the visualization */ + QList waypoints; + waypoints.clear(); + int numWaypoints = objManager->getNumInstances(waypointObj->getObjID()); + for (int i = 0; i < numWaypoints; i++) { + Waypoint *waypoint = Waypoint::GetInstance(objManager, i); + Q_ASSERT(waypoint); + if(waypoint == NULL) + return; + + waypoints.append(UavoToInternal(waypoint->getData())); + } + + /* Inform visualization */ emit visualizationChanged(waypoints); } + +/** + * Convert a UAVO waypoint to the local structure + * @param uavo The UAVO data representation + * @return The waypoint structure for visualization + */ +struct PathCompiler::waypoint PathCompiler::UavoToInternal(Waypoint::DataFields uavo) +{ + double homeLLA[3]; + double LLA[3]; + double NED[3]; + struct PathCompiler::waypoint internalWaypoint; + + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(homeLocation); + if (homeLocation == NULL) + return internalWaypoint; + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + homeLLA[0] = homeLocationData.Latitude / 10e6; + homeLLA[1] = homeLocationData.Longitude / 10e6; + homeLLA[2] = homeLocationData.Altitude; + + NED[0] = uavo.Position[Waypoint::POSITION_NORTH]; + NED[1] = uavo.Position[Waypoint::POSITION_EAST]; + NED[2] = uavo.Position[Waypoint::POSITION_DOWN]; + Utils::CoordinateConversions().GetLLA(homeLLA, NED, LLA); + + internalWaypoint.latitude = LLA[0]; + internalWaypoint.longitude = LLA[1]; + return internalWaypoint; +} + +/** + * Convert a UAVO waypoint to the local structure + * @param internal The internal structure type + * @returns The waypoint UAVO data structure + */ +Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint /*internal*/) +{ + Waypoint::DataFields uavo; + return uavo; +} + diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index f0e71aae4..47aced375 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -30,6 +30,7 @@ #include #include #include +#include // TODO: Make this a singleton class and separate from map library. Not sure of the proper design pattern in Qt. // factory? static variables? @@ -47,23 +48,26 @@ public: explicit PathCompiler(QObject *parent = 0); //! This method opens a dialog (if filename is null) and saves the path - int savePath(QString filename = null); + int savePath(QString filename = NULL); //! This method opens a dialog (if filename is null) and loads the path - int loadPath(QString filename = null); + int loadPath(QString filename = NULL); //! Waypoint representation that is exchanged between visualization struct waypoint { - float latitude; - float longitude; + double latitude; + double longitude; }; private: //! Helper method to get uavobject manager UAVObjectManager * getObjectManager(); - //! The internal list of waypoints - QList waypoints; + //! Convert a UAVO waypoint to the local structure + struct PathCompiler::waypoint UavoToInternal(Waypoint::DataFields); + + //! Convert a UAVO waypoint to the local structure + Waypoint::DataFields InternalToUavo(struct waypoint); signals: /** From 6b662f9b9eccd618955be02f56157342572bf10f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 12:43:41 -0500 Subject: [PATCH 013/508] Connect OPMapGadget to the PathCompiler so any changes in UAVOs are reflected on the map --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 24 ++++++++++++++++++- .../src/plugins/opmap/opmapgadgetwidget.h | 4 ++++ 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index cda08c258..aa00d144e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -40,7 +40,7 @@ #include "homelocation.h" #include "positionactual.h" - +#include #include #include "utils/stylehelper.h" @@ -145,6 +145,10 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_magic_waypoint.time_seconds = 0; m_magic_waypoint.hold_time_seconds = 0; + // Connect to the path compiler to get updates from the waypoints + pathCompiler = new PathCompiler(this); + connect(pathCompiler,SIGNAL(visualizationChanged(QList)), + this, SLOT(doVisualizationChanged(QList))); // ************** // create the widget that holds the user controls and the map @@ -2416,3 +2420,21 @@ void OPMapGadgetWidget::SetUavPic(QString UAVPic) { m_map->SetUavPic(UAVPic); } + +/** + * Called from path compiler whenever the path to visualize has changed + */ +void OPMapGadgetWidget::doVisualizationChanged(QList waypoints) +{ + m_map->WPDeleteAll(); + foreach (PathCompiler::waypoint waypoint, waypoints) { + internals::PointLatLng position(waypoint.latitude, waypoint.longitude); + + WayPointItem * wayPointItem = m_map->WPCreate(position, 0, "Waypoint"); + Q_ASSERT(wayPointItem); + if(wayPointItem) { + wayPointItem->setFlag(QGraphicsItem::ItemIsMovable, false); + wayPointItem->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + } + } +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index b5728a79b..65f4e25b9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -53,6 +53,7 @@ #include "uavobject.h" #include "objectpersistence.h" +#include // ****************************************************** namespace Ui @@ -182,6 +183,7 @@ private slots: void WPValuesChanged(WayPointItem* waypoint); void WPInserted(int const& number, WayPointItem* waypoint); void WPDeleted(int const& number); + void doVisualizationChanged(QList); /** * @brief mouse right click context menu signals @@ -267,7 +269,9 @@ private: mapcontrol::WayPointItem *m_mouse_waypoint; + PathCompiler *pathCompiler; QList m_waypoint_list; + QMutex m_waypoint_list_mutex; QMutex m_map_mutex; From 7492c8fec8fc8f842192ff4b32003cb974852083 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 12:59:57 -0500 Subject: [PATCH 014/508] UI Fix: Remove unnecessary spacer (that triggered a warning) from input page --- .../openpilotgcs/src/plugins/config/input.ui | 43 +++++++------------ 1 file changed, 15 insertions(+), 28 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 422904bb5..672256e20 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -239,7 +239,7 @@ Configure each stabilization mode for each axis - + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); @@ -256,7 +256,7 @@ margin:1px; - + Stabilized1 @@ -266,7 +266,7 @@ margin:1px; - + @@ -279,7 +279,7 @@ margin:1px; - + @@ -292,7 +292,7 @@ margin:1px; - + @@ -305,7 +305,7 @@ margin:1px; - + Stabilized2 @@ -315,28 +315,28 @@ margin:1px; - + Qt::StrongFocus - + Qt::StrongFocus - + Qt::StrongFocus - + Stabilized3 @@ -346,28 +346,28 @@ margin:1px; - + Qt::StrongFocus - + Qt::StrongFocus - + Qt::StrongFocus - + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); @@ -384,20 +384,7 @@ margin:1px; - - - - Qt::Vertical - - - - 20 - 20 - - - - - + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); From f7e0fc1065daebb2d8680982fcd04173dbaf92f6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 13:28:10 -0500 Subject: [PATCH 015/508] Add a long comment describing pathcompiler and store the index for each waypoint in their description. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 4 +++- ground/openpilotgcs/src/plugins/opmap/pathcompiler.h | 12 ++++++++++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index aa00d144e..031eb6079 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2427,14 +2427,16 @@ void OPMapGadgetWidget::SetUavPic(QString UAVPic) void OPMapGadgetWidget::doVisualizationChanged(QList waypoints) { m_map->WPDeleteAll(); + int index = 0; foreach (PathCompiler::waypoint waypoint, waypoints) { internals::PointLatLng position(waypoint.latitude, waypoint.longitude); - WayPointItem * wayPointItem = m_map->WPCreate(position, 0, "Waypoint"); + WayPointItem * wayPointItem = m_map->WPCreate(position, 0, QString(index)); Q_ASSERT(wayPointItem); if(wayPointItem) { wayPointItem->setFlag(QGraphicsItem::ItemIsMovable, false); wayPointItem->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + index++; } } } diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 47aced375..db5639c9d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -40,6 +40,18 @@ * UAVObject representation on the flight controller. It also can support multiple * ways of converting a path from what the user clicked to the underlying representation * to achieve the desired end flight trajectory + * + * So the chain of data for the map lib is: + * FC <-> PathCompiler <-> OPMapGadget <-> OPMapLib + * + * The goal is that PathCompiler be as state free as is possible. Eventually for more + * complicated path compilation this will probably not be achievable. That means it + * should not cache a copy of waypoints locally if that can be avoided (i.e. it should + * refer directly to what is stored on the FC). + * + * For the visualization to have the ability to manipulate the path though it needs to + * be able to map unambiguously from the graphical items to the internal waypoints. It + * must cache a lookup from the graphical item to the index from this tool. */ class PathCompiler : public QObject { From 4e1044589f0d4170bfa4c30cbfdf5c4fa6dfdd2a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 14:28:52 -0500 Subject: [PATCH 016/508] Add a coordinate conversion method to go from LLA to NED --- .../src/libs/utils/coordinateconversions.cpp | 23 +++++++++++++++++++ .../src/libs/utils/coordinateconversions.h | 1 + 2 files changed, 24 insertions(+) diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp index 4f1835f4f..62579bddc 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp @@ -143,6 +143,29 @@ int CoordinateConversions::GetLLA(double homeLLA[3], double NED[3], double posit return 0; } +/** + * Get the current location in Longitude, Latitude Altitude (above WSG-48 ellipsoid) + * @param[in] BaseECEF the ECEF of the home location (in cm) + * @param[in] position three element double for position in degrees and meters + * @param[out] NED the offset from the home location (in m) + * @returns + * @arg 0 success + * @arg -1 for failure + */ +int CoordinateConversions::GetNED(double homeLLA[3], double position[3], double NED[3]) +{ + double T[3]; + T[0] = homeLLA[2]+6.378137E6f * M_PI / 180.0; + T[1] = cosf(homeLLA[0] * M_PI / 180.0)*(homeLLA[2]+6.378137E6f) * M_PI / 180.0; + T[2] = -1.0f; + + NED[0] = (position[0] - homeLLA[0]) * T[0]; + NED[1] = (position[1] - homeLLA[1]) * T[1]; + NED[2] = (position[2] - homeLLA[2]) * T[2]; + + return 0; +} + void CoordinateConversions::LLA2Base(double LLA[3], double BaseECEF[3], float Rne[3][3], float NED[3]) { double ECEF[3]; diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h index f6f47a8d7..bc0e7a9c5 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h @@ -42,6 +42,7 @@ class QTCREATOR_UTILS_EXPORT CoordinateConversions public: CoordinateConversions(); int GetLLA(double LLA[3], double NED[3], double position[3]); + int GetNED(double homeLLA[3], double position[3], double NED[3]); void RneFromLLA(double LLA[3], double Rne[3][3]); void LLA2ECEF(double LLA[3], double ECEF[3]); int ECEF2LLA(double ECEF[3], double LLA[3]); From 64ba15cf07290d41c0ff4e05e8acc1b4cd745f10 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 14:29:22 -0500 Subject: [PATCH 017/508] Add the ability to add waypoints via OPMap --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 39 +++---------- .../src/plugins/opmap/pathcompiler.cpp | 55 ++++++++++++++++++- 2 files changed, 61 insertions(+), 33 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 031eb6079..da41019e7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin @@ -1898,42 +1898,19 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) void OPMapGadgetWidget::onAddWayPointAct_triggered() { + Q_ASSERT(m_widget); + Q_ASSERT(m_map); + if (!m_widget || !m_map) return; if (m_map_mode != Normal_MapMode) return; - m_waypoint_list_mutex.lock(); - - // create a waypoint on the map at the last known mouse position - t_waypoint *wp = new t_waypoint; - wp->map_wp_item = NULL; - wp->coord = m_context_menu_lat_lon; - wp->altitude = 0; - wp->description = ""; - wp->locked = false; - wp->time_seconds = 0; - wp->hold_time_seconds = 0; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - - if (wp->map_wp_item) - { - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - - // and remember it in our own local waypoint list - m_waypoint_list.append(wp); - - m_waypoint_list_mutex.unlock(); + struct PathCompiler::waypoint newWaypoint; + newWaypoint.latitude = m_context_menu_lat_lon.Lat(); + newWaypoint.longitude = m_context_menu_lat_lon.Lng(); + pathCompiler->doAddWaypoint(newWaypoint); } /** diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 640c75ade..fc28c95a4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -93,9 +93,28 @@ int PathCompiler::loadPath(QString filename) * @param waypoint the new waypoint to add * @param position which position to insert it to, defaults to end */ -void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint, int /* position */) +void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint waypoint, int /*position*/) { + UAVObjectManager *objMngr; + objMngr = getObjectManager(); + if (objMngr == NULL) + return; + /* TODO: If a waypoint is inserted not at the end shift them all by one and */ + /* add the data there */ + + Waypoint *obj = new Waypoint(); + Q_ASSERT(obj); + if (obj) { + // Register a new waypoint instance + quint32 newInstId = objMngr->getNumInstances(obj->getObjID()); + obj->initialize(newInstId,obj->getMetaObject()); + objMngr->registerObject(obj); + + // Set the data in the new object + Waypoint::DataFields newWaypoint = InternalToUavo(waypoint); + obj->setData(newWaypoint); + } } /** @@ -181,9 +200,41 @@ struct PathCompiler::waypoint PathCompiler::UavoToInternal(Waypoint::DataFields * @param internal The internal structure type * @returns The waypoint UAVO data structure */ -Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint /*internal*/) +Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint internal) { Waypoint::DataFields uavo; + + double homeLLA[3]; + double LLA[3]; + double NED[3]; + struct PathCompiler::waypoint internalWaypoint; + + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(homeLocation); + if (homeLocation == NULL) + return uavo; + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + homeLLA[0] = homeLocationData.Latitude / 10e6; + homeLLA[1] = homeLocationData.Longitude / 10e6; + homeLLA[2] = homeLocationData.Altitude; + + // TODO: Give the point a concept of altitude + LLA[0] = internal.latitude; + LLA[1] = internal.longitude; + LLA[2] = -50; + + Utils::CoordinateConversions().GetNED(homeLLA, LLA, NED); + + uavo.Position[Waypoint::POSITION_NORTH] = NED[0]; + uavo.Position[Waypoint::POSITION_EAST] = NED[1]; + uavo.Position[Waypoint::POSITION_DOWN] = NED[2]; + + uavo.Action = Waypoint::ACTION_NEXT; + + uavo.Velocity[Waypoint::VELOCITY_NORTH] = 5; + uavo.Velocity[Waypoint::VELOCITY_EAST] = 0; + uavo.Velocity[Waypoint::VELOCITY_DOWN] = 0; + return uavo; } From e686ac0b1dc38f5c6a94b31d382f05fe7259bee9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 15:02:43 -0500 Subject: [PATCH 018/508] Start adding the ability to delete a waypoint --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 68 ++++--------------- .../src/plugins/opmap/pathcompiler.cpp | 10 ++- .../src/plugins/opmap/pathcompiler.h | 5 ++ 3 files changed, 29 insertions(+), 54 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index da41019e7..1ca72597b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1957,52 +1957,22 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() void OPMapGadgetWidget::onDeleteWayPointAct_triggered() { + Q_ASSERT(m_widget); + Q_ASSERT(m_map); + if (!m_widget || !m_map) return; if (m_map_mode != Normal_MapMode) return; - if (!m_mouse_waypoint) - return; + Q_ASSERT(m_mouse_waypoint); + if(m_mouse_waypoint) { + int waypointIdx = m_mouse_waypoint->Description().toInt(); - bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; - - if (locked) return; // waypoint is locked - - QMutexLocker locker(&m_waypoint_list_mutex); - - for (int i = 0; i < m_waypoint_list.count(); i++) - { - t_waypoint *wp = m_waypoint_list.at(i); - if (!wp) continue; - if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; - - // delete the waypoint from the map - m_map->WPDelete(wp->map_wp_item); - - // delete the waypoint from our local waypoint list - m_waypoint_list.removeAt(i); - - delete wp; - - break; - } - - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; - - // delete the waypoint from the map - m_map->WPDelete(wp->map_wp_item); - - // delete the waypoint from our local waypoint list - m_waypoint_list.removeOne(wp); - - delete wp; - - break; + Q_ASSERT(pathCompiler); + if(pathCompiler) + pathCompiler->doDelWaypoint(waypointIdx); } m_mouse_waypoint = NULL; @@ -2013,26 +1983,18 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() */ void OPMapGadgetWidget::onClearWayPointsAct_triggered() { + Q_ASSERT(m_widget); + Q_ASSERT(m_map); + if (!m_widget || !m_map) return; if (m_map_mode != Normal_MapMode) return; - QMutexLocker locker(&m_waypoint_list_mutex); - - m_map->WPDeleteAll(); - - foreach (t_waypoint *wp, m_waypoint_list) - { - if (wp) - { - delete wp; - wp = NULL; - } - } - - m_waypoint_list.clear(); + Q_ASSERT(pathCompiler); + if(pathCompiler) + pathCompiler->doDelAllWaypoints(); } void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index fc28c95a4..daa7ecd47 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -121,7 +121,7 @@ void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint waypoint, int /*p * Delete a waypoint * @param index which waypoint to delete */ -void PathCompiler::doDelWaypoint(int /*index*/) +void PathCompiler::doDelWaypoint(int index) { // This method is awkward because there is no support // on the FC for actually deleting a waypoint. We need @@ -132,6 +132,14 @@ void PathCompiler::doDelWaypoint(int /*index*/) Q_ASSERT(false); } +/** + * Delete all the waypoints + */ +void PathCompiler::doDelAllWaypoints() +{ + +} + /** * When the UAV waypoints change trigger the pathcompiler to * get the latest version and then update the visualization diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index db5639c9d..426d94c55 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -109,6 +109,11 @@ public slots: */ void doDelWaypoint(int index); + /** + * Delete all the waypoints + */ + void doDelAllWaypoints(); + public slots: /** * These are slots that the UAV can call to update the path. From 4ad23864c8de7cf16e6b8740ddf35f18b7452856 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 15:07:40 -0500 Subject: [PATCH 019/508] Treat the waypoint action as something to do once you hit that location. (e.g. PathToNext) and add a Stop value to indicate not to advance to the next waypoint. This is essentially a perament loiter to the pathfollower (I think) but it's really just to have the ability to "delete" waypoints. --- flight/Modules/PathPlanner/pathplanner.c | 28 ++++++++++++---------- shared/uavobjectdefinition/pathdesired.xml | 2 +- shared/uavobjectdefinition/waypoint.xml | 2 +- 3 files changed, 18 insertions(+), 14 deletions(-) diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index 57f617560..0f4707ce0 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -146,7 +146,7 @@ static void pathPlannerTask(void *parameters) // We hit this waypoint if (r2 < (MIN_RADIUS * MIN_RADIUS)) { switch(waypoint.Action) { - case WAYPOINT_ACTION_NEXT: + case WAYPOINT_ACTION_PATHTONEXT: waypointActive.Index++; WaypointActiveSet(&waypointActive); @@ -160,6 +160,8 @@ static void pathPlannerTask(void *parameters) pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; PathDesiredSet(&pathDesired); break; + case WAYPOINT_ACTION_STOP: + break; default: PIOS_DEBUG_Assert(0); } @@ -179,7 +181,7 @@ static void pathPlannerTask(void *parameters) if (progress.fractional_progress >= 1) { switch(waypoint.Action) { - case WAYPOINT_ACTION_NEXT: + case WAYPOINT_ACTION_PATHTONEXT: waypointActive.Index++; WaypointActiveSet(&waypointActive); @@ -193,6 +195,8 @@ static void pathPlannerTask(void *parameters) pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; PathDesiredSet(&pathDesired); break; + case WAYPOINT_ACTION_STOP: + break; default: PIOS_DEBUG_Assert(0); } @@ -300,7 +304,7 @@ static void createPathBox() // Draw O WaypointData waypoint; waypoint.Velocity[0] = 2; // Since for now this isn't directional just set a mag - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; waypoint.Position[0] = 5; waypoint.Position[1] = 5; @@ -337,7 +341,7 @@ static void createPathLogo() waypoint.Position[1] = 30 * cos(i / 19.0 * 2 * M_PI); waypoint.Position[0] = 50 * sin(i / 19.0 * 2 * M_PI); waypoint.Position[2] = -50; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); bad_inits += (WaypointInstSet(i, &waypoint) != 0); } @@ -347,7 +351,7 @@ static void createPathLogo() waypoint.Position[1] = 55 + 20 * cos(i / 10.0 * M_PI - M_PI / 2); waypoint.Position[0] = 25 + 25 * sin(i / 10.0 * M_PI - M_PI / 2); waypoint.Position[2] = -50; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); bad_inits += (WaypointInstSet(i, &waypoint) != 0); } @@ -355,7 +359,7 @@ static void createPathLogo() waypoint.Position[1] = 35; waypoint.Position[0] = -50; waypoint.Position[2] = -50; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(35, &waypoint); @@ -363,42 +367,42 @@ static void createPathLogo() waypoint.Position[1] = 35; waypoint.Position[0] = -60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(36, &waypoint); waypoint.Position[1] = 85; waypoint.Position[0] = -60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(37, &waypoint); waypoint.Position[1] = 85; waypoint.Position[0] = 60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(38, &waypoint); waypoint.Position[1] = -40; waypoint.Position[0] = 60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(39, &waypoint); waypoint.Position[1] = -40; waypoint.Position[0] = -60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(40, &waypoint); waypoint.Position[1] = 35; waypoint.Position[0] = -60; waypoint.Position[2] = -30; - waypoint.Action = WAYPOINT_ACTION_NEXT; + waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(41, &waypoint); diff --git a/shared/uavobjectdefinition/pathdesired.xml b/shared/uavobjectdefinition/pathdesired.xml index b9816c2bd..788efbcf5 100644 --- a/shared/uavobjectdefinition/pathdesired.xml +++ b/shared/uavobjectdefinition/pathdesired.xml @@ -7,7 +7,7 @@ - + diff --git a/shared/uavobjectdefinition/waypoint.xml b/shared/uavobjectdefinition/waypoint.xml index 9a6ce5da7..344a59792 100644 --- a/shared/uavobjectdefinition/waypoint.xml +++ b/shared/uavobjectdefinition/waypoint.xml @@ -4,7 +4,7 @@ - + From 39657af8db8a357cad6840d34eb8c47b31b007db Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 15:37:44 -0500 Subject: [PATCH 020/508] More work on deleting waypoints --- .../src/plugins/opmap/pathcompiler.cpp | 58 +++++++++++++++++-- .../src/plugins/opmap/pathcompiler.h | 5 ++ 2 files changed, 57 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index daa7ecd47..a170cdb90 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -128,8 +128,38 @@ void PathCompiler::doDelWaypoint(int index) // to shift them all by one and set the new "last" waypoint // to a stop action - // Not implemented yet - Q_ASSERT(false); + UAVObjectManager *objManager = getObjectManager(); + Waypoint *waypoint = Waypoint::GetInstance(objManager); + Q_ASSERT(waypoint); + if (!waypoint) + return; + + int numWaypoints = objManager->getNumInstances(waypoint->getObjID()); + for (int i = index; i < numWaypoints - 1; i++) { + Waypoint *waypointDest = Waypoint::GetInstance(objManager, i); + Q_ASSERT(waypointDest); + + Waypoint *waypointSrc = Waypoint::GetInstance(objManager, i + 1); + Q_ASSERT(waypointSrc); + + if (!waypointDest || !waypointSrc) + return; + + // Copy the data down an index + waypointDest->setData(waypointSrc->getData()); + } + + // Set the second to last waypoint to stop (and last for safety) + // the functional equivalent to deleting + for (int i = numWaypoints - 2; i < numWaypoints; i++) { + waypoint = Waypoint::GetInstance(objManager, i); + Q_ASSERT(waypoint); + if (waypoint) { + Waypoint::DataFields waypointData = waypoint->getData(); + waypointData.Action = Waypoint::ACTION_STOP; + waypoint->setData(waypointData); + } + } } /** @@ -137,7 +167,21 @@ void PathCompiler::doDelWaypoint(int index) */ void PathCompiler::doDelAllWaypoints() { + Waypoint *waypointObj = Waypoint::GetInstance(getObjectManager(), 0); + Q_ASSERT(waypointObj); + if (waypointObj == NULL) + return; + int numWaypoints = getObjectManager()->getNumInstances(waypointObj->getObjID()); + for (int i = 0; i < numWaypoints; i++) { + Waypoint *waypoint = Waypoint::GetInstance(getObjectManager(), i); + Q_ASSERT(waypoint); + if (waypoint) { + Waypoint::DataFields waypointData = waypoint->getData(); + waypointData.Action = Waypoint::ACTION_STOP; + waypoint->setData(waypointData); + } + } } /** @@ -159,13 +203,16 @@ void PathCompiler::doUpdateFromUAV() QList waypoints; waypoints.clear(); int numWaypoints = objManager->getNumInstances(waypointObj->getObjID()); - for (int i = 0; i < numWaypoints; i++) { + bool stopped = false; + for (int i = 0; i < numWaypoints && !stopped; i++) { Waypoint *waypoint = Waypoint::GetInstance(objManager, i); Q_ASSERT(waypoint); if(waypoint == NULL) return; - waypoints.append(UavoToInternal(waypoint->getData())); + Waypoint::DataFields waypointData = waypoint->getData(); + waypoints.append(UavoToInternal(waypointData)); + stopped = waypointData.Action == Waypoint::ACTION_STOP; } /* Inform visualization */ @@ -215,7 +262,6 @@ Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint internal) double homeLLA[3]; double LLA[3]; double NED[3]; - struct PathCompiler::waypoint internalWaypoint; HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(homeLocation); @@ -237,7 +283,7 @@ Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint internal) uavo.Position[Waypoint::POSITION_EAST] = NED[1]; uavo.Position[Waypoint::POSITION_DOWN] = NED[2]; - uavo.Action = Waypoint::ACTION_NEXT; + uavo.Action = Waypoint::ACTION_PATHTONEXT; uavo.Velocity[Waypoint::VELOCITY_NORTH] = 5; uavo.Velocity[Waypoint::VELOCITY_EAST] = 0; diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 426d94c55..b52ee8e89 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -103,6 +103,11 @@ public slots: */ void doAddWaypoint(struct PathCompiler::waypoint, int position = -1); + /** + * Update waypoint + */ + //void doUpdateWaypoints(struct PathCompiler::waypoint, int position); + /** * Delete a waypoint * @param index which waypoint to delete From 3ac14fccb766091810f2f34aed65ef5297002083 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 16:36:46 -0500 Subject: [PATCH 021/508] Change waypoints to update on change --- shared/uavobjectdefinition/waypoint.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/waypoint.xml b/shared/uavobjectdefinition/waypoint.xml index 344a59792..33c145212 100644 --- a/shared/uavobjectdefinition/waypoint.xml +++ b/shared/uavobjectdefinition/waypoint.xml @@ -7,7 +7,7 @@ - + From 484057e9ae5c8af1e943789038562f5aaa237b6d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 16:43:17 -0500 Subject: [PATCH 022/508] Revert "Change waypoints to update on change" This reverts commit 2e5c34b8efce01810f2da26c1b7b54a70e90daad. --- shared/uavobjectdefinition/waypoint.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/waypoint.xml b/shared/uavobjectdefinition/waypoint.xml index 33c145212..344a59792 100644 --- a/shared/uavobjectdefinition/waypoint.xml +++ b/shared/uavobjectdefinition/waypoint.xml @@ -7,7 +7,7 @@ - + From 0a842ac6391e8a9abfc82d090addb6f47b53f270 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 17:45:55 -0500 Subject: [PATCH 023/508] After deleting a waypoint (which really sets the last one to stop and shifts the rest) any added waypoints were invisible. This puts the new one after the first stop and removes the stop. --- .../src/plugins/opmap/pathcompiler.cpp | 67 ++++++++++++++----- 1 file changed, 52 insertions(+), 15 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index a170cdb90..b122b3390 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -31,6 +31,8 @@ #include #include +#include + PathCompiler::PathCompiler(QObject *parent) : QObject(parent) { @@ -95,25 +97,54 @@ int PathCompiler::loadPath(QString filename) */ void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint waypoint, int /*position*/) { - UAVObjectManager *objMngr; - objMngr = getObjectManager(); - if (objMngr == NULL) - return; - /* TODO: If a waypoint is inserted not at the end shift them all by one and */ /* add the data there */ - Waypoint *obj = new Waypoint(); - Q_ASSERT(obj); - if (obj) { - // Register a new waypoint instance - quint32 newInstId = objMngr->getNumInstances(obj->getObjID()); - obj->initialize(newInstId,obj->getMetaObject()); - objMngr->registerObject(obj); + UAVObjectManager *objManager = getObjectManager(); - // Set the data in the new object - Waypoint::DataFields newWaypoint = InternalToUavo(waypoint); - obj->setData(newWaypoint); + // Format the data from the map into a UAVO + Waypoint::DataFields newWaypoint = InternalToUavo(waypoint); + + // Search for any waypoints set to stop, because if they exist we + // should add the waypoint immediately after that one + int numWaypoints = objManager->getNumInstances(Waypoint::OBJID); + int i; + for (i = 0; i < numWaypoints; i++) { + Waypoint *waypoint = Waypoint::GetInstance(objManager, i); + Q_ASSERT(waypoint); + if(waypoint == NULL) + return; + + Waypoint::DataFields waypointData = waypoint->getData(); + if(waypointData.Action == Waypoint::ACTION_STOP) { + waypointData.Action = Waypoint::ACTION_PATHTONEXT; + waypoint->setData(waypointData); + break; + } + } + + if (i >= numWaypoints - 1) { + // We reached end of list so new waypoint needs to be registered + + Waypoint *waypoint = new Waypoint(); + Q_ASSERT(waypoint); + if (waypoint) { + // Register a new waypoint instance + quint32 newInstId = objManager->getNumInstances(waypoint->getObjID()); + waypoint->initialize(newInstId,waypoint->getMetaObject()); + objManager->registerObject(waypoint); + + // Set the data in the new object + waypoint->setData(newWaypoint); + waypoint->updated(); + } + } else { + Waypoint *waypoint = Waypoint::GetInstance(objManager, i + 1); + Q_ASSERT(waypoint); + if (waypoint) { + waypoint->setData(newWaypoint); + waypoint->updated(); + } } } @@ -136,6 +167,7 @@ void PathCompiler::doDelWaypoint(int index) int numWaypoints = objManager->getNumInstances(waypoint->getObjID()); for (int i = index; i < numWaypoints - 1; i++) { + qDebug() << "Copying from" << i+1 << "to" << i; Waypoint *waypointDest = Waypoint::GetInstance(objManager, i); Q_ASSERT(waypointDest); @@ -152,6 +184,7 @@ void PathCompiler::doDelWaypoint(int index) // Set the second to last waypoint to stop (and last for safety) // the functional equivalent to deleting for (int i = numWaypoints - 2; i < numWaypoints; i++) { + qDebug() << "Stopping" << i; waypoint = Waypoint::GetInstance(objManager, i); Q_ASSERT(waypoint); if (waypoint) { @@ -160,6 +193,8 @@ void PathCompiler::doDelWaypoint(int index) waypoint->setData(waypointData); } } + + waypoint->updated(); } /** @@ -182,6 +217,8 @@ void PathCompiler::doDelAllWaypoints() waypoint->setData(waypointData); } } + + waypointObj->updated(); } /** From 8aab4755e44be9e25096ebba1a2fdbfb50ed9c3f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 18:35:28 -0500 Subject: [PATCH 024/508] Try and cover a case that was making the waypointitem crash --- .../libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 89c180f2d..8f1892a61 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -97,8 +97,14 @@ namespace mapcontrol { if(event->button()==Qt::LeftButton) { - delete text; - delete textBG; + if(text) { + delete text; + text = NULL; + } + if(textBG) { + delete textBG; + textBG = NULL; + } coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); isDragging=false; RefreshToolTip(); From e82621cbeb615b9364c79a13297d6e8d461048c9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 2 Jun 2012 18:36:00 -0500 Subject: [PATCH 025/508] Fix waypoint deletion --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 33 ++++++++----------- .../src/plugins/opmap/pathcompiler.cpp | 7 ++-- 2 files changed, 18 insertions(+), 22 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 1ca72597b..eca598fcd 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1332,23 +1332,6 @@ void OPMapGadgetWidget::setMapMode(opMapModeType mode) } m_map->WPDeleteAll(); - // restore the normal waypoints on the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - if (!wp->map_wp_item) continue; - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - m_waypoint_list_mutex.unlock(); - break; case MagicWaypoint_MapMode: @@ -1896,6 +1879,10 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) m_map->UAV->SetTrailDistance(trail_distance); } +/** + * Called when the add waypoint menu item is selected + * the coordinate clicked is in m_context_menu_lat_lon + */ void OPMapGadgetWidget::onAddWayPointAct_triggered() { Q_ASSERT(m_widget); @@ -1955,6 +1942,10 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() m_mouse_waypoint = NULL; } +/** + * Called when the delete waypoint menu item is selected + * the waypoint clicked is in m_mouse_waypoint + */ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() { Q_ASSERT(m_widget); @@ -1968,8 +1959,12 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() Q_ASSERT(m_mouse_waypoint); if(m_mouse_waypoint) { - int waypointIdx = m_mouse_waypoint->Description().toInt(); + int waypointIdx = m_mouse_waypoint->Number(); + if(waypointIdx < 0) { + qDebug() << "WTF Map gadget. Wrong number"; + return; + } Q_ASSERT(pathCompiler); if(pathCompiler) pathCompiler->doDelWaypoint(waypointIdx); @@ -2373,7 +2368,7 @@ void OPMapGadgetWidget::doVisualizationChanged(QList way WayPointItem * wayPointItem = m_map->WPCreate(position, 0, QString(index)); Q_ASSERT(wayPointItem); if(wayPointItem) { - wayPointItem->setFlag(QGraphicsItem::ItemIsMovable, false); + wayPointItem->setFlag(QGraphicsItem::ItemIsMovable, true); wayPointItem->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); index++; } diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index b122b3390..c1c7890a3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -178,7 +178,9 @@ void PathCompiler::doDelWaypoint(int index) return; // Copy the data down an index - waypointDest->setData(waypointSrc->getData()); + Waypoint::DataFields waypoint = waypointSrc->getData(); + waypointDest->setData(waypoint); + waypointDest->updated(); } // Set the second to last waypoint to stop (and last for safety) @@ -191,10 +193,9 @@ void PathCompiler::doDelWaypoint(int index) Waypoint::DataFields waypointData = waypoint->getData(); waypointData.Action = Waypoint::ACTION_STOP; waypoint->setData(waypointData); + waypoint->updated(); } } - - waypoint->updated(); } /** From c892a28970829f0a2754187aeacb2028e0be0477 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 3 Jun 2012 09:36:21 -0500 Subject: [PATCH 026/508] Fix firmware to work with new usage of the action waypoint field --- flight/Modules/PathPlanner/pathplanner.c | 185 +++++++++++++---------- 1 file changed, 101 insertions(+), 84 deletions(-) diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index 0f4707ce0..562e40f2e 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -54,12 +54,17 @@ static WaypointActiveData waypointActive; static WaypointData waypoint; // Private functions +static void advanceWaypoint(); +static void checkTerminationCondition(); +static void activateWaypoint(); + static void pathPlannerTask(void *parameters); static void settingsUpdated(UAVObjEvent * ev); static void waypointsUpdated(UAVObjEvent * ev); static void createPathBox(); static void createPathLogo(); +static int32_t active_waypoint = -1; /** * Module initialization */ @@ -107,11 +112,7 @@ static void pathPlannerTask(void *parameters) WaypointActiveConnectCallback(waypointsUpdated); FlightStatusData flightStatus; - PathDesiredData pathDesired; - PositionActualData positionActual; - const float MIN_RADIUS = 4.0f; // Radius to consider at waypoint (m) - // Main thread loop bool pathplanner_active = false; while (1) @@ -124,6 +125,8 @@ static void pathPlannerTask(void *parameters) pathplanner_active = false; continue; } + + checkTerminationCondition(); if(pathplanner_active == false) { // This triggers callback to update variable @@ -135,75 +138,6 @@ static void pathPlannerTask(void *parameters) continue; } - switch(pathPlannerSettings.PathMode) { - case PATHPLANNERSETTINGS_PATHMODE_ENDPOINT: - PositionActualGet(&positionActual); - - float r2 = powf(positionActual.North - waypoint.Position[WAYPOINT_POSITION_NORTH], 2) + - powf(positionActual.East - waypoint.Position[WAYPOINT_POSITION_EAST], 2) + - powf(positionActual.Down - waypoint.Position[WAYPOINT_POSITION_DOWN], 2); - - // We hit this waypoint - if (r2 < (MIN_RADIUS * MIN_RADIUS)) { - switch(waypoint.Action) { - case WAYPOINT_ACTION_PATHTONEXT: - waypointActive.Index++; - WaypointActiveSet(&waypointActive); - - break; - case WAYPOINT_ACTION_RTH: - // Fly back to the home location but 20 m above it - PathDesiredGet(&pathDesired); - pathDesired.End[PATHDESIRED_END_NORTH] = 0; - pathDesired.End[PATHDESIRED_END_EAST] = 0; - pathDesired.End[PATHDESIRED_END_DOWN] = -20; - pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; - PathDesiredSet(&pathDesired); - break; - case WAYPOINT_ACTION_STOP: - break; - default: - PIOS_DEBUG_Assert(0); - } - } - - break; - - case PATHPLANNERSETTINGS_PATHMODE_PATH: - - PathDesiredGet(&pathDesired); - PositionActualGet(&positionActual); - - float cur[3] = {positionActual.North, positionActual.East, positionActual.Down}; - struct path_status progress; - - path_progress(pathDesired.Start, pathDesired.End, cur, &progress); - - if (progress.fractional_progress >= 1) { - switch(waypoint.Action) { - case WAYPOINT_ACTION_PATHTONEXT: - waypointActive.Index++; - WaypointActiveSet(&waypointActive); - - break; - case WAYPOINT_ACTION_RTH: - // Fly back to the home location but 20 m above it - PathDesiredGet(&pathDesired); - pathDesired.End[PATHDESIRED_END_NORTH] = 0; - pathDesired.End[PATHDESIRED_END_EAST] = 0; - pathDesired.End[PATHDESIRED_END_DOWN] = -20; - pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; - PathDesiredSet(&pathDesired); - break; - case WAYPOINT_ACTION_STOP: - break; - default: - PIOS_DEBUG_Assert(0); - } - } - - break; - } } } @@ -219,25 +153,109 @@ static void waypointsUpdated(UAVObjEvent * ev) return; WaypointActiveGet(&waypointActive); - WaypointInstGet(waypointActive.Index, &waypoint); + if(active_waypoint != waypointActive.Index) + activateWaypoint(waypointActive.Index); +} + +/** + * This method checks the current position against the active waypoint + * to determine if it has been reached + */ +static void checkTerminationCondition() +{ + const float MIN_RADIUS = 4.0f; // Radius to consider at waypoint (m) + + PositionActualData positionActual; + PathDesiredData pathDesired; + + switch(waypoint.Action) { + case WAYPOINT_ACTION_ENDPOINTTONEXT: + PositionActualGet(&positionActual); + + float r2 = powf(positionActual.North - waypoint.Position[WAYPOINT_POSITION_NORTH], 2) + + powf(positionActual.East - waypoint.Position[WAYPOINT_POSITION_EAST], 2) + + powf(positionActual.Down - waypoint.Position[WAYPOINT_POSITION_DOWN], 2); + + // We hit this waypoint + if (r2 < (MIN_RADIUS * MIN_RADIUS)) + advanceWaypoint(); + + break; + + case WAYPOINT_ACTION_PATHTONEXT: + + PathDesiredGet(&pathDesired); + PositionActualGet(&positionActual); + + float cur[3] = {positionActual.North, positionActual.East, positionActual.Down}; + struct path_status progress; + + path_progress(pathDesired.Start, pathDesired.End, cur, &progress); + + if (progress.fractional_progress >= 1) + advanceWaypoint(); + + break; + case WAYPOINT_ACTION_STOP: + // Never advance even when you hit a stop waypoint + break; + } + +} + +/** + * Increment the waypoint index which triggers the active waypoint method + */ +static void advanceWaypoint() +{ + WaypointActiveGet(&waypointActive); + waypointActive.Index++; + WaypointActiveSet(&waypointActive); +} + +/** + * This method is called when a new waypoint is activated + */ +static void activateWaypoint(int idx) +{ + active_waypoint = idx; + + uint8_t waypoint_mode = WAYPOINT_ACTION_PATHTONEXT; + if (idx > 0) { + WaypointData prevWaypoint; + WaypointInstGet(idx - 1, &prevWaypoint); + waypoint_mode = prevWaypoint.Action; + } PathDesiredData pathDesired; - switch(pathPlannerSettings.PathMode) { - case PATHPLANNERSETTINGS_PATHMODE_ENDPOINT: + switch(waypoint_mode) { + case WAYPOINT_ACTION_RTH: { + PathDesiredGet(&pathDesired); + pathDesired.End[PATHDESIRED_END_NORTH] = 0; + pathDesired.End[PATHDESIRED_END_EAST] = 0; + pathDesired.End[PATHDESIRED_END_DOWN] = -50; // TODO: Get alt from somewhere? + pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; + PathDesiredSet(&pathDesired); + } + break; + case WAYPOINT_ACTION_ENDPOINTTONEXT: + { + WaypointInstGet(idx, &waypoint); + PathDesiredGet(&pathDesired); pathDesired.End[PATHDESIRED_END_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; pathDesired.End[PATHDESIRED_END_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; pathDesired.End[PATHDESIRED_END_DOWN] = -waypoint.Position[WAYPOINT_POSITION_DOWN]; pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; PathDesiredSet(&pathDesired); - } break; - - case PATHPLANNERSETTINGS_PATHMODE_PATH: + case WAYPOINT_ACTION_PATHTONEXT: { + WaypointInstGet(idx, &waypoint); + PathDesiredData pathDesired; pathDesired.End[PATHDESIRED_END_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; @@ -251,7 +269,7 @@ static void waypointsUpdated(UAVObjEvent * ev) // Get current position as start point PositionActualData positionActual; PositionActualGet(&positionActual); - + pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down - 1; @@ -260,19 +278,18 @@ static void waypointsUpdated(UAVObjEvent * ev) // Get previous waypoint as start point WaypointData waypointPrev; WaypointInstGet(waypointActive.Index - 1, &waypointPrev); - + pathDesired.Start[PATHDESIRED_END_NORTH] = waypointPrev.Position[WAYPOINT_POSITION_NORTH]; pathDesired.Start[PATHDESIRED_END_EAST] = waypointPrev.Position[WAYPOINT_POSITION_EAST]; pathDesired.Start[PATHDESIRED_END_DOWN] = waypointPrev.Position[WAYPOINT_POSITION_DOWN]; pathDesired.StartingVelocity = sqrtf(powf(waypointPrev.Velocity[WAYPOINT_VELOCITY_NORTH],2) + - powf(waypointPrev.Velocity[WAYPOINT_VELOCITY_EAST],2)); - + powf(waypointPrev.Velocity[WAYPOINT_VELOCITY_EAST],2)); } - PathDesiredSet(&pathDesired); } break; } + } void settingsUpdated(UAVObjEvent * ev) { From b06b51f1b2addcc6fa20a37208b5947e81eb544b Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 31 May 2012 16:41:03 +0200 Subject: [PATCH 027/508] Revolution/Attitude: Added offset calculation for barometric altitude --- flight/Modules/Attitude/revolution/attitude.c | 22 ++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 18bc20630..f6d157408 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -77,6 +77,8 @@ #define F_PI 3.14159265358979323846f #define PI_MOD(x) (fmodf(x + F_PI, F_PI * 2) - F_PI) + +#define BaroOffsetLowPassTime 300 // low pass filter settle time aprox 5 minutes TODO: make a setting // Private types // Private variables @@ -506,6 +508,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) static bool gps_updated; static bool gps_vel_updated; + static float baroOffset = 0; + static uint32_t ins_last_time = 0; static bool inited; @@ -576,7 +580,10 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) float Pdiag[16]={25.0f,25.0f,25.0f,5.0f,5.0f,5.0f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-5f,1e-4f,1e-4f,1e-4f}; float q[4]; float pos[3] = {0.0f, 0.0f, 0.0f}; - pos[2] = baroData.Altitude * -1.0f; + + // Initialize barometric offset to homelocation altitude + baroOffset = -home.Altitude; + pos[2] = -(baroData.Altitude + baroOffset); // Reset the INS algorithm INSGPSInit(); @@ -621,6 +628,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // Transform the GPS position into NED coordinates getNED(&gpsPosition, NED); + + // Initialize barometric offset to cirrent GPS NED coordinate + baroOffset = -NED[2] - baroData.Altitude; xQueueReceive(magQueue, &ev, 100 / portTICK_RATE_MS); MagnetometerGet(&magData); @@ -732,6 +742,12 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // Transform the GPS position into NED coordinates getNED(&gpsData, NED); + // Track barometric altitude offset with a low pass filter + if (baro_updated) { + baroOffset = (1.0f - (dT/BaroOffsetLowPassTime)) * baroOffset + (dT/BaroOffsetLowPassTime) * + ( -NED[2] - baroData.Altitude ); + } + // Store this for inspecting offline NEDPositionData nedPos; NEDPositionGet(&nedPos); @@ -744,7 +760,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetPosVelVar(1e2f, 1e2f); vel[0] = vel[1] = vel[2] = 0; NED[0] = NED[1] = 0; - NED[2] = baroData.Altitude; + NED[2] = -(baroData.Altitude + baroOffset); sensors |= HORIZ_SENSORS | HORIZ_POS_SENSORS; sensors |= POS_SENSORS |VERT_SENSORS; } @@ -761,7 +777,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) * although probably should occur within INS itself */ if (sensors) - INSCorrection(&magData.x, NED, vel, baroData.Altitude, sensors); + INSCorrection(&magData.x, NED, vel, ( baroData.Altitude + baroOffset ), sensors); // Copy the position and velocity into the UAVO PositionActualData positionActual; From be72d24c5f2c42fb7da0002a16068fdb48e7ded7 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 31 May 2012 18:21:20 +0200 Subject: [PATCH 028/508] Attitude: Fixed calculation for baro offset adjustment time --- flight/Modules/Attitude/revolution/attitude.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index f6d157408..3bebe73c0 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -78,7 +78,11 @@ #define F_PI 3.14159265358979323846f #define PI_MOD(x) (fmodf(x + F_PI, F_PI * 2) - F_PI) -#define BaroOffsetLowPassTime 300 // low pass filter settle time aprox 5 minutes TODO: make a setting +// low pass filter configuration to calculate offset +// of barometric altitude sensor +// reasoning: updates at: 10 Hz, tau= 300 s settle time +// exp(-(1/f) / tau ) ~=~ 0.9997 +#define BARO_OFFSET_LOWPASS_ALPHA 0.9997f // Private types // Private variables @@ -582,7 +586,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) float pos[3] = {0.0f, 0.0f, 0.0f}; // Initialize barometric offset to homelocation altitude - baroOffset = -home.Altitude; + baroOffset = -baroData.Altitude; pos[2] = -(baroData.Altitude + baroOffset); // Reset the INS algorithm @@ -743,10 +747,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) getNED(&gpsData, NED); // Track barometric altitude offset with a low pass filter - if (baro_updated) { - baroOffset = (1.0f - (dT/BaroOffsetLowPassTime)) * baroOffset + (dT/BaroOffsetLowPassTime) * - ( -NED[2] - baroData.Altitude ); - } + baroOffset = BARO_OFFSET_LOWPASS_ALPHA * baroOffset + + (1.0f - BARO_OFFSET_LOWPASS_ALPHA ) + * ( -NED[2] - baroData.Altitude ); // Store this for inspecting offline NEDPositionData nedPos; From a3df27ab65901513fa0607bbba0f2fde0daae671 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 3 Jun 2012 16:45:18 -0500 Subject: [PATCH 029/508] Need to call FLASH_OB_Launch after setting the BOR bits --- flight/Bootloaders/Revolution/main.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Bootloaders/Revolution/main.c b/flight/Bootloaders/Revolution/main.c index 9084df31b..6fb4fd8e6 100644 --- a/flight/Bootloaders/Revolution/main.c +++ b/flight/Bootloaders/Revolution/main.c @@ -221,6 +221,8 @@ void check_bor() if(bor != OB_BOR_LEVEL3) { FLASH_OB_Unlock(); FLASH_OB_BORConfig(OB_BOR_LEVEL3); + FLASH_OB_Launch(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); FLASH_OB_Lock(); while(FLASH_WaitForLastOperation() == FLASH_BUSY); } From 2ec84233343d212b85a9e8084d87c6aaaa970a5e Mon Sep 17 00:00:00 2001 From: Sambas Date: Sun, 27 May 2012 22:15:31 +0300 Subject: [PATCH 030/508] Mag calibration, does this make any sense? --- .../src/plugins/config/configrevowidget.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 61e0eacd0..dc2b0eea2 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -571,12 +572,16 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z void ConfigRevoWidget::computeScaleBias() { double S[3], b[3]; + double Be_lenght; RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); + Q_ASSERT(homeLocation); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); - // Calibration accel - SixPointInConstFieldCal( GRAVITY, accel_data_x, accel_data_y, accel_data_z, S, b); + // Calibration accel + SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); @@ -586,7 +591,8 @@ void ConfigRevoWidget::computeScaleBias() revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; // Calibration mag - SixPointInConstFieldCal( 1000, mag_data_x, mag_data_y, mag_data_z, S, b); + Be_lenght = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); + SixPointInConstFieldCal( Be_lenght, mag_data_x, mag_data_y, mag_data_z, S, b); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); From eb4f90f188bab2cbb8377ea23e762b6cc61300e6 Mon Sep 17 00:00:00 2001 From: Sambas Date: Mon, 28 May 2012 17:19:03 +0300 Subject: [PATCH 031/508] Check if Homelocation is set before calibration --- .../src/plugins/config/configrevowidget.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index dc2b0eea2..f13fc863f 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include #include @@ -614,8 +615,23 @@ void ConfigRevoWidget::computeScaleBias() void ConfigRevoWidget::sixPointCalibrationMode() { RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); + Q_ASSERT(homeLocation); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + + //check if Homelocation is set + if(!homeLocationData.Set) + { + QMessageBox msgBox; + msgBox.setInformativeText(tr("

HomeLocation not SET.

Please set your HomeLocation and try again. Aborting calibration!

")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.setIcon(QMessageBox::Information); + msgBox.exec(); + return; + } // Calibration accel revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = 1; From 34a4f159b27d4e86a2dc507131bcc9bea44302f9 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 2 Jun 2012 20:26:41 -0400 Subject: [PATCH 032/508] makefile: pass build type (BL/FW/BU/EF) into sub-makes --- Makefile | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Makefile b/Makefile index 2a0b16e50..99d49db1f 100644 --- a/Makefile +++ b/Makefile @@ -530,6 +530,7 @@ fw_$(1)_%: uavobjects_flight $(V1) cd $(ROOT_DIR)/flight/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BUILD_TYPE=fw \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ $$* @@ -553,6 +554,7 @@ bl_$(1)_%: $(V1) cd $(ROOT_DIR)/flight/Bootloaders/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BUILD_TYPE=bl \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ $$* @@ -587,6 +589,7 @@ bu_$(1)_%: bl_$(1)_bino $(V1) cd $(ROOT_DIR)/flight/Bootloaders/BootloaderUpdater && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BUILD_TYPE=bu \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ $$* @@ -607,6 +610,7 @@ ef_$(1)_%: bl_$(1)_bin fw_$(1)_opfw $(V1) cd $(ROOT_DIR)/flight/EntireFlash && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BUILD_TYPE=ef \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ DFU_CMD="$(DFUUTIL_DIR)/bin/dfu-util" \ $$* From fbb6df8ebf4236b62adcc97a0f4d03ca6d9ce9d2 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 2 Jun 2012 20:27:58 -0400 Subject: [PATCH 033/508] makefile: pass short name (CC/PIPX/REVO) into sub-makes --- Makefile | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/Makefile b/Makefile index 99d49db1f..e0f65fd67 100644 --- a/Makefile +++ b/Makefile @@ -520,6 +520,7 @@ uavobjects_clean: # $(1) = Canonical board name all in lower case (e.g. coptercontrol) # $(2) = Name of board used in source tree (e.g. CopterControl) +# $(3) = Short name for board (e.g CC) define FW_TEMPLATE .PHONY: $(1) fw_$(1) $(1): fw_$(1)_opfw @@ -530,6 +531,7 @@ fw_$(1)_%: uavobjects_flight $(V1) cd $(ROOT_DIR)/flight/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BOARD_SHORT_NAME=$(3) \ BUILD_TYPE=fw \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ @@ -554,6 +556,7 @@ bl_$(1)_%: $(V1) cd $(ROOT_DIR)/flight/Bootloaders/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BOARD_SHORT_NAME=$(3) \ BUILD_TYPE=bl \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ @@ -589,6 +592,7 @@ bu_$(1)_%: bl_$(1)_bino $(V1) cd $(ROOT_DIR)/flight/Bootloaders/BootloaderUpdater && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BOARD_SHORT_NAME=$(3) \ BUILD_TYPE=bu \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ @@ -610,6 +614,7 @@ ef_$(1)_%: bl_$(1)_bin fw_$(1)_opfw $(V1) cd $(ROOT_DIR)/flight/EntireFlash && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ + BOARD_SHORT_NAME=$(3) \ BUILD_TYPE=ef \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ DFU_CMD="$(DFUUTIL_DIR)/bin/dfu-util" \ @@ -644,6 +649,13 @@ pipxtreme_friendly := PipXtreme revolution_friendly := Revolution simposix_friendly := SimPosix +# Short hames of each board (used to display board name in parallel builds) +coptercontrol_short := 'cc ' +pipxtreme_short := 'pipx' +revolution_short := 'revo' +simposix_short := 'posx' +osd_short := 'osd ' + # Start out assuming that we'll build fw, bl and bu for all boards FW_BOARDS := $(ALL_BOARDS) BL_BOARDS := $(ALL_BOARDS) @@ -690,16 +702,16 @@ all_flight_clean: all_fw_clean all_bl_clean all_bu_clean all_ef_clean $(foreach board, $(ALL_BOARDS), $(eval $(call BOARD_PHONY_TEMPLATE,$(board)))) # Expand the bootloader updater rules -$(foreach board, $(ALL_BOARDS), $(eval $(call BU_TEMPLATE,$(board),$($(board)_friendly)))) +$(foreach board, $(ALL_BOARDS), $(eval $(call BU_TEMPLATE,$(board),$($(board)_friendly),$($(board)_short)))) # Expand the firmware rules -$(foreach board, $(ALL_BOARDS), $(eval $(call FW_TEMPLATE,$(board),$($(board)_friendly)))) +$(foreach board, $(ALL_BOARDS), $(eval $(call FW_TEMPLATE,$(board),$($(board)_friendly),$($(board)_short)))) # Expand the bootloader rules -$(foreach board, $(ALL_BOARDS), $(eval $(call BL_TEMPLATE,$(board),$($(board)_friendly)))) +$(foreach board, $(ALL_BOARDS), $(eval $(call BL_TEMPLATE,$(board),$($(board)_friendly),$($(board)_short)))) # Expand the entire-flash rules -$(foreach board, $(ALL_BOARDS), $(eval $(call EF_TEMPLATE,$(board),$($(board)_friendly)))) +$(foreach board, $(ALL_BOARDS), $(eval $(call EF_TEMPLATE,$(board),$($(board)_friendly),$($(board)_short)))) .PHONY: sim_win32 sim_win32: sim_win32_exe From ec0889ea85e83994c945fe506c7e55019ae2c0fb Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 2 Jun 2012 20:31:57 -0400 Subject: [PATCH 034/508] makefile: add additional context to output when building all_* targets When building the various all_* targets, it was hard to tell which board/build-type that each line of output applied to. Now, the all_* target types will include something like: CC [fw|cc ] flight/PiOS/STM32F10x/pios_gpio.c which includes the necessary additional context. This will help with identifying the context for warnings and errors when building a group of targets. --- Makefile | 9 +++++- flight/EntireFlash/Makefile | 4 +-- make/firmware-defs.mk | 57 +++++++++++++++++++++---------------- 3 files changed, 43 insertions(+), 27 deletions(-) diff --git a/Makefile b/Makefile index e0f65fd67..749319360 100644 --- a/Makefile +++ b/Makefile @@ -626,6 +626,13 @@ ef_$(1)_clean: $(V1) $(RM) -fr $(BUILD_DIR)/ef_$(1) endef +# When building any of the "all_*" targets, tell all sub makefiles to display +# additional details on each line of output to describe which build and target +# that each line applies to. +ifneq ($(strip $(filter all_%,$(MAKECMDGOALS))),) +export ENABLE_MSG_EXTRA := yes +endif + # $(1) = Canonical board name all in lower case (e.g. coptercontrol) define BOARD_PHONY_TEMPLATE .PHONY: all_$(1) @@ -723,7 +730,7 @@ sim_win32_%: uavobjects_flight .PHONY: sim_osx sim_osx: sim_osx_elf - + sim_osx_%: uavobjects_flight $(V1) mkdir -p $(BUILD_DIR)/sim_osx $(V1) $(MAKE) --no-print-directory \ diff --git a/flight/EntireFlash/Makefile b/flight/EntireFlash/Makefile index c4fda382f..548461a24 100644 --- a/flight/EntireFlash/Makefile +++ b/flight/EntireFlash/Makefile @@ -35,13 +35,13 @@ bin: $(OUTDIR)/$(TARGET).bin FW_PAD = $(shell echo $$[$(FW_BANK_BASE)-$(BL_BANK_BASE)-$(BL_BANK_SIZE)]) $(OUTDIR)/$(TARGET).pad: - $(V0) @echo " PADDING $@" + $(V0) @echo $(MSG_PADDING) $@ $(V1) dd status=noxfer if=/dev/zero count=$(FW_PAD) bs=1 2>/dev/null | tr '\000' '\377' > $@ BL_BIN = $(TOP)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin FW_BIN = $(TOP)/build/fw_$(BOARD_NAME)/fw_$(BOARD_NAME).bin $(OUTDIR)/$(TARGET).bin: $(BL_BIN) $(FW_BIN) $(OUTDIR)/$(TARGET).pad - $(V0) @echo " FLASH IMG $@" + $(V0) @echo $(MSG_FLASH_IMG) $@ $(V1) cat $(BL_BIN) $(OUTDIR)/$(TARGET).pad $(FW_BIN) > $@ .PHONY: dfu diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index 32f2f60bc..3ead53444 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -23,32 +23,41 @@ else quote = endif +# Add a board designator to the terse message text +ifeq ($(ENABLE_MSG_EXTRA),yes) + MSG_EXTRA := [$(BUILD_TYPE)|$(BOARD_SHORT_NAME)] +else + MSG_BOARD := +endif + # Define Messages # English -MSG_FORMATERROR := ${quote} Can not handle output-format${quote} -MSG_MODINIT := ${quote} MODINIT ${quote} -MSG_SIZE := ${quote} SIZE ${quote} -MSG_LOAD_FILE := ${quote} BIN/HEX ${quote} -MSG_BIN_OBJ := ${quote} BINO ${quote} -MSG_STRIP_FILE := ${quote} STRIP ${quote} -MSG_EXTENDED_LISTING := ${quote} LIS ${quote} -MSG_SYMBOL_TABLE := ${quote} NM ${quote} -MSG_LINKING := ${quote} LD ${quote} -MSG_COMPILING := ${quote} CC ${quote} -MSG_COMPILING_ARM := ${quote} CC-ARM ${quote} -MSG_COMPILINGCPP := ${quote} CXX ${quote} -MSG_COMPILINGCPP_ARM := ${quote} CXX-ARM ${quote} -MSG_ASSEMBLING := ${quote} AS ${quote} -MSG_ASSEMBLING_ARM := ${quote} AS-ARM ${quote} -MSG_CLEANING := ${quote} CLEAN ${quote} -MSG_ASMFROMC := ${quote} AS(C) ${quote} -MSG_ASMFROMC_ARM := ${quote} AS(C)-ARM ${quote} -MSG_PYMITEINIT := ${quote} PY ${quote} -MSG_INSTALLING := ${quote} INSTALL ${quote} -MSG_OPFIRMWARE := ${quote} OPFW ${quote} -MSG_FWINFO := ${quote} FWINFO ${quote} -MSG_JTAG_PROGRAM := ${quote} JTAG-PGM ${quote} -MSG_JTAG_WIPE := ${quote} JTAG-WIPE ${quote} +MSG_FORMATERROR = ${quote} Can not handle output-format${quote} +MSG_MODINIT = ${quote} MODINIT $(MSG_EXTRA) ${quote} +MSG_SIZE = ${quote} SIZE $(MSG_EXTRA) ${quote} +MSG_LOAD_FILE = ${quote} BIN/HEX $(MSG_EXTRA) ${quote} +MSG_BIN_OBJ = ${quote} BINO $(MSG_EXTRA) ${quote} +MSG_STRIP_FILE = ${quote} STRIP $(MSG_EXTRA) ${quote} +MSG_EXTENDED_LISTING = ${quote} LIS $(MSG_EXTRA) ${quote} +MSG_SYMBOL_TABLE = ${quote} NM $(MSG_EXTRA) ${quote} +MSG_LINKING = ${quote} LD $(MSG_EXTRA) ${quote} +MSG_COMPILING = ${quote} CC ${MSG_EXTRA} ${quote} +MSG_COMPILING_ARM = ${quote} CC-ARM $(MSG_EXTRA) ${quote} +MSG_COMPILINGCPP = ${quote} CXX $(MSG_EXTRA) ${quote} +MSG_COMPILINGCPP_ARM = ${quote} CXX-ARM $(MSG_EXTRA) ${quote} +MSG_ASSEMBLING = ${quote} AS $(MSG_EXTRA) ${quote} +MSG_ASSEMBLING_ARM = ${quote} AS-ARM $(MSG_EXTRA) ${quote} +MSG_CLEANING = ${quote} CLEAN $(MSG_EXTRA) ${quote} +MSG_ASMFROMC = ${quote} AS(C) $(MSG_EXTRA) ${quote} +MSG_ASMFROMC_ARM = ${quote} AS(C)-ARM $(MSG_EXTRA) ${quote} +MSG_PYMITEINIT = ${quote} PY $(MSG_EXTRA) ${quote} +MSG_INSTALLING = ${quote} INSTALL $(MSG_EXTRA) ${quote} +MSG_OPFIRMWARE = ${quote} OPFW $(MSG_EXTRA) ${quote} +MSG_FWINFO = ${quote} FWINFO $(MSG_EXTRA) ${quote} +MSG_JTAG_PROGRAM = ${quote} JTAG-PGM $(MSG_EXTRA) ${quote} +MSG_JTAG_WIPE = ${quote} JTAG-WIPE $(MSG_EXTRA) ${quote} +MSG_PADDING = ${quote} PADDING $(MSG_EXTRA) ${quote} +MSG_FLASH_IMG = ${quote} FLASH_IMG $(MSG_EXTRA) ${quote} toprel = $(subst $(realpath $(TOP))/,,$(abspath $(1))) From 434d89bd3001410bb0a35223d92c6f56a2803fa9 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 2 Jun 2012 20:37:28 -0400 Subject: [PATCH 035/508] makefile: enable extra context when building multiple targets Extra message context is also useful even when building more than one target in the same invocation of make. This example would enable extra context: make fw_coptercontrol bl_coptercontrol --- Makefile | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Makefile b/Makefile index 749319360..a8ac4ab42 100644 --- a/Makefile +++ b/Makefile @@ -633,6 +633,12 @@ ifneq ($(strip $(filter all_%,$(MAKECMDGOALS))),) export ENABLE_MSG_EXTRA := yes endif +# When building more than one goal in a single make invocation, also +# enable the extra context for each output line +ifneq ($(word 2,$(MAKECMDGOALS)),) +export ENABLE_MSG_EXTRA := yes +endif + # $(1) = Canonical board name all in lower case (e.g. coptercontrol) define BOARD_PHONY_TEMPLATE .PHONY: all_$(1) From 21eb48c58c0641de191ff730cda4c44f1544ee6b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 3 Jun 2012 21:18:20 -0500 Subject: [PATCH 036/508] Add a RTH flight mode and remove it from the waypoint actions as that is redundant with flying to (0,0,0) --- .../Modules/ManualControl/inc/manualcontrol.h | 3 +- flight/Modules/ManualControl/manualcontrol.c | 29 ++++++++++++++++++- flight/Modules/PathPlanner/pathplanner.c | 10 ------- .../VtolPathFollower/vtolpathfollower.c | 8 +++++ shared/uavobjectdefinition/flightstatus.xml | 2 +- .../manualcontrolsettings.xml | 2 +- shared/uavobjectdefinition/waypoint.xml | 2 +- 7 files changed, 41 insertions(+), 15 deletions(-) diff --git a/flight/Modules/ManualControl/inc/manualcontrol.h b/flight/Modules/ManualControl/inc/manualcontrol.h index 406d8cfb0..5444793fa 100644 --- a/flight/Modules/ManualControl/inc/manualcontrol.h +++ b/flight/Modules/ManualControl/inc/manualcontrol.h @@ -42,7 +42,8 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : \ - (x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) ? FLIGHTMODE_GUIDANCE : FLIGHTMODE_UNDEFINED \ + (x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) ? FLIGHTMODE_GUIDANCE : \ + (x == FLIGHTSTATUS_FLIGHTMODE_RTH) ? FLIGHTMODE_GUIDANCE : FLIGHTMODE_UNDEFINED \ ) int32_t ManualControlInitialize(); diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 1b74e096c..cfc78f27e 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -85,6 +85,7 @@ static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed); static void updatePathDesired(ManualControlCommandData * cmd, bool changed); +static void setRTH(ManualControlCommandData * cmd, bool changed); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void setArmedIfChanged(uint8_t val); @@ -397,6 +398,9 @@ static void manualControlTask(void *parameters) case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; + case FLIGHTSTATUS_FLIGHTMODE_RTH: + setRTH(&cmd, lastFlightMode != flightStatus.FlightMode); + break; default: AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); } @@ -614,7 +618,24 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon } #if defined(REVOLUTION) -// TODO: Need compile flag to exclude this from copter control +static void setRTH(ManualControlCommandData * cmd, bool changed) +{ + if(changed) { + PositionActualData positionActual; + PositionActualGet(&positionActual); + + PathDesiredData pathDesired; + PathDesiredGet(&pathDesired); + + // Attempt to fly to home 10 m above the current location + pathDesired.End[PATHDESIRED_END_NORTH] = 0; + pathDesired.End[PATHDESIRED_END_EAST] = 0; + pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down - 10; + pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; + PathDesiredSet(&pathDesired); + } +} + /** * @brief Update the position desired to current location when * enabled and allow the waypoint to be moved by transmitter @@ -699,6 +720,12 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) // TODO: These functions should never be accessible on CC. Any configuration that // could allow them to be called sholud already throw an error to prevent this happening // in flight + +static void setRTH(ManualControlCommandData * cmd, bool changed) +{ + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); +} + static void updatePathDesired(ManualControlCommandData * cmd, bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index 562e40f2e..4dc4db5c0 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -230,16 +230,6 @@ static void activateWaypoint(int idx) PathDesiredData pathDesired; switch(waypoint_mode) { - case WAYPOINT_ACTION_RTH: - { - PathDesiredGet(&pathDesired); - pathDesired.End[PATHDESIRED_END_NORTH] = 0; - pathDesired.End[PATHDESIRED_END_EAST] = 0; - pathDesired.End[PATHDESIRED_END_DOWN] = -50; // TODO: Get alt from somewhere? - pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; - PathDesiredSet(&pathDesired); - } - break; case WAYPOINT_ACTION_ENDPOINTTONEXT: { WaypointInstGet(idx, &waypoint); diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 5568983d5..9887089e7 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -178,6 +178,14 @@ static void vtolPathFollowerTask(void *parameters) // Check the combinations of flightmode and pathdesired mode switch(flightStatus.FlightMode) { + case FLIGHTSTATUS_FLIGHTMODE_RTH: + if (pathDesired.Mode == PATHDESIRED_MODE_ENDPOINT) { + updateEndpointVelocity(); + updateVtolDesiredAttitude(); + } else { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); + } + break; case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: if (pathDesired.Mode == PATHDESIRED_MODE_ENDPOINT) { updateEndpointVelocity(); diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 555617065..716250923 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -4,7 +4,7 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 9ccc10b47..f84218105 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -23,7 +23,7 @@ - + diff --git a/shared/uavobjectdefinition/waypoint.xml b/shared/uavobjectdefinition/waypoint.xml index 344a59792..f6f61e61e 100644 --- a/shared/uavobjectdefinition/waypoint.xml +++ b/shared/uavobjectdefinition/waypoint.xml @@ -4,7 +4,7 @@ - + From 10aa31a57f07e4efa6a61ac7c89d0c5f0d46e0d0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 3 Jun 2012 23:17:48 -0500 Subject: [PATCH 037/508] When ManualControlSettings.FailsafeBehavior is set to RTH and no valid input is detected and the aircraft is armed enter RTH mode. --- flight/Modules/ManualControl/manualcontrol.c | 68 ++++++++++++++++--- .../manualcontrolsettings.xml | 1 + 2 files changed, 60 insertions(+), 9 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index cfc78f27e..16f9e664a 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -40,6 +40,7 @@ #include "baroaltitude.h" #include "flighttelemetrystats.h" #include "flightstatus.h" +#include "guidancesettings.h" #include "manualcontrol.h" #include "manualcontrolsettings.h" #include "manualcontrolcommand.h" @@ -85,9 +86,10 @@ static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed); static void updatePathDesired(ManualControlCommandData * cmd, bool changed); -static void setRTH(ManualControlCommandData * cmd, bool changed); +static void setRTH(bool changed); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData * settings); static void setArmedIfChanged(uint8_t val); static void manualControlTask(void *parameters); @@ -228,9 +230,9 @@ static void manualControlTask(void *parameters) // If a channel has timed out this is not valid data and we shouldn't update anything // until we decide to go to failsafe - if(cmd.Channel[n] == PIOS_RCVR_TIMEOUT) + if(cmd.Channel[n] == PIOS_RCVR_TIMEOUT) { valid_input_detected = false; - else + } else scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); } @@ -364,9 +366,12 @@ static void manualControlTask(void *parameters) processFlightMode(&settings, flightMode); } - - // Process arming outside conditional so system will disarm when disconnected - processArm(&cmd, &settings); + + if (processFailsafe(valid_input_detected, &settings) == false) { + // Process arming outside conditional so system will disarm when disconnected. However don't do + // it when in failsafe mode + processArm(&cmd, &settings); + } // Update cmd object ManualControlCommandSet(&cmd); @@ -399,7 +404,7 @@ static void manualControlTask(void *parameters) updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; case FLIGHTSTATUS_FLIGHTMODE_RTH: - setRTH(&cmd, lastFlightMode != flightStatus.FlightMode); + setRTH(lastFlightMode != flightStatus.FlightMode); break; default: AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); @@ -618,7 +623,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon } #if defined(REVOLUTION) -static void setRTH(ManualControlCommandData * cmd, bool changed) +static void setRTH(bool changed) { if(changed) { PositionActualData positionActual; @@ -636,6 +641,46 @@ static void setRTH(ManualControlCommandData * cmd, bool changed) } } +static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData *settings) +{ + static bool failsafe_enaged = false; + + if (valid_input_detected) { + failsafe_enaged = false; + } else if (!failsafe_enaged) { + switch(settings->FailsafeBehavior) { + case MANUALCONTROLSETTINGS_FAILSAFEBEHAVIOR_NONE: + failsafe_enaged = false; + break; + case MANUALCONTROLSETTINGS_FAILSAFEBEHAVIOR_RTH: + { + GuidanceSettingsData guidanceSettings; + GuidanceSettingsGet(&guidanceSettings); + + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + // Only makes sense to try and RTH if the AP is controlling throttle and we are + // already armed. It would be _really_ nice to have some indication we are actively + // flying to put here. I would like to check the throttle is engaged but that would + // exclude fixed wing. + if (guidanceSettings.ThrottleControl == GUIDANCESETTINGS_THROTTLECONTROL_TRUE && + flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { + + setRTH(true); + flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_RTH; + failsafe_enaged = true; + } + } + break; + } + } else if (failsafe_enaged) { + // Eventually process more sophisticated behavior here like triggering landing + } + + return failsafe_enaged; +} + /** * @brief Update the position desired to current location when * enabled and allow the waypoint to be moved by transmitter @@ -721,7 +766,12 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) // could allow them to be called sholud already throw an error to prevent this happening // in flight -static void setRTH(ManualControlCommandData * cmd, bool changed) +static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData *settings) +{ + return false; +} + +static void setRTH(bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index f84218105..25733439e 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -26,6 +26,7 @@ + From dc7fe1bdd8dc55c095c1cde385b2310767189210 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 00:31:32 -0500 Subject: [PATCH 038/508] Try and get pios_gcsrcvr working on simulation and revo for testing RTH. Had to include uavobjectmanager.h manually which was weird --- flight/PiOS.osx/inc/pios_gcsrcvr_priv.h | 47 ++++++ flight/PiOS.osx/osx/pios_gcsrcvr.c | 139 ++++++++++++++++++ flight/Revolution/Makefile.osx | 2 +- flight/Revolution/System/inc/pios_board_sim.h | 1 + .../Revolution/System/inc/pios_config_sim.h | 1 + flight/Revolution/System/pios_board_sim.c | 15 +- flight/Revolution/UAVObjects.inc | 1 + .../board_hw_defs/revolution/board_hw_defs.c | 7 +- 8 files changed, 207 insertions(+), 6 deletions(-) create mode 100644 flight/PiOS.osx/inc/pios_gcsrcvr_priv.h create mode 100644 flight/PiOS.osx/osx/pios_gcsrcvr.c diff --git a/flight/PiOS.osx/inc/pios_gcsrcvr_priv.h b/flight/PiOS.osx/inc/pios_gcsrcvr_priv.h new file mode 100644 index 000000000..ded416423 --- /dev/null +++ b/flight/PiOS.osx/inc/pios_gcsrcvr_priv.h @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_GCSRCVR GCS Receiver Functions + * @brief PIOS interface to read from GCS receiver port + * @{ + * + * @file pios_gcsrcvr_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GCS receiver private functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_GCSRCVR_PRIV_H +#define PIOS_GCSRCVR_PRIV_H + +#include + +#include "gcsreceiver.h" + +extern const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver; + +extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id); + +#endif /* PIOS_GCSRCVR_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS.osx/osx/pios_gcsrcvr.c b/flight/PiOS.osx/osx/pios_gcsrcvr.c new file mode 100644 index 000000000..f9c19cca3 --- /dev/null +++ b/flight/PiOS.osx/osx/pios_gcsrcvr.c @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_GCSRCVR GCS Receiver Input Functions + * @brief Code to read the channels within the GCS Receiver UAVObject + * @{ + * + * @file pios_gcsrcvr.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GCS Input functions (STM32 dependent) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "openpilot.h" +#include "pios_gcsrcvr_priv.h" + +static GCSReceiverData gcsreceiverdata; + +/* Provide a RCVR driver */ +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel); + +const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver = { + .read = PIOS_GCSRCVR_Get, +}; + +/* Local Variables */ +enum pios_gcsrcvr_dev_magic { + PIOS_GCSRCVR_DEV_MAGIC = 0xe9da5c56, +}; + +struct pios_gcsrcvr_dev { + enum pios_gcsrcvr_dev_magic magic; + + uint8_t supv_timer; + bool Fresh; +}; + +static struct pios_gcsrcvr_dev *global_gcsrcvr_dev; + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_gcsrcvr_dev *PIOS_gcsrcvr_alloc(void) +{ + struct pios_gcsrcvr_dev * gcsrcvr_dev; + + gcsrcvr_dev = (struct pios_gcsrcvr_dev *)pvPortMalloc(sizeof(*gcsrcvr_dev)); + if (!gcsrcvr_dev) return(NULL); + + gcsrcvr_dev->magic = PIOS_GCSRCVR_DEV_MAGIC; + gcsrcvr_dev->Fresh = FALSE; + gcsrcvr_dev->supv_timer = 0; + + /* The update callback cannot receive the device pointer, so set it in a global */ + global_gcsrcvr_dev = gcsrcvr_dev; + + return(gcsrcvr_dev); +} +#else +static struct pios_gcsrcvr_dev pios_gcsrcvr_devs[PIOS_GCSRCVR_MAX_DEVS]; +static uint8_t pios_gcsrcvr_num_devs; +static struct pios_gcsrcvr_dev *PIOS_gcsrcvr_alloc(void) +{ + struct pios_gcsrcvr_dev *gcsrcvr_dev; + + if (pios_gcsrcvr_num_devs >= PIOS_GCSRCVR_MAX_DEVS) { + return (NULL); + } + + gcsrcvr_dev = &pios_gcsrcvr_devs[pios_gcsrcvr_num_devs++]; + gcsrcvr_dev->magic = PIOS_GCSRCVR_DEV_MAGIC; + gcsrcvr_dev->Fresh = FALSE; + gcsrcvr_dev->supv_timer = 0; + + global_gcsrcvr_dev = gcsrcvr_dev; + + return (gcsrcvr_dev); +} +#endif + +static void gcsreceiver_updated(UAVObjEvent * ev) +{ + struct pios_gcsrcvr_dev *gcsrcvr_dev = global_gcsrcvr_dev; + if (ev->obj == GCSReceiverHandle()) { + GCSReceiverGet(&gcsreceiverdata); + gcsrcvr_dev->Fresh = TRUE; + } +} + +extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id) +{ + struct pios_gcsrcvr_dev *gcsrcvr_dev; + + /* Allocate the device structure */ + gcsrcvr_dev = (struct pios_gcsrcvr_dev *)PIOS_gcsrcvr_alloc(); + if (!gcsrcvr_dev) + return -1; + + /* Register uavobj callback */ + GCSReceiverConnectCallback (gcsreceiver_updated); + + return 0; +} + +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel) +{ + if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) { + /* channel is out of range */ + return -1; + } + + return (gcsreceiverdata.Channel[channel]); +} + +#endif /* PIOS_INCLUDE_GCSRCVR */ + +/** + * @} + * @} + */ diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index ca7d5a5c8..bc1f50988 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -180,7 +180,7 @@ SRC += $(PIOSPOSIX)/pios_wdg.c SRC += $(PIOSPOSIX)/pios_debug.c SRC += $(PIOSPOSIX)/pios_rcvr.c -#SRC += $(PIOSPOSIX)/pios_sim.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c diff --git a/flight/Revolution/System/inc/pios_board_sim.h b/flight/Revolution/System/inc/pios_board_sim.h index 3d6264e69..30a3d3d37 100644 --- a/flight/Revolution/System/inc/pios_board_sim.h +++ b/flight/Revolution/System/inc/pios_board_sim.h @@ -63,6 +63,7 @@ extern uint32_t pios_com_spectrum_id; #define PIOS_COM_DEBUG (PIOS_COM_AUX #endif +#define PIOS_GCSRCVR_TIMEOUT_MS 200 /** * glue macros for file IO * STM32 uses DOSFS for file IO diff --git a/flight/Revolution/System/inc/pios_config_sim.h b/flight/Revolution/System/inc/pios_config_sim.h index db1881387..e7f7aed82 100644 --- a/flight/Revolution/System/inc/pios_config_sim.h +++ b/flight/Revolution/System/inc/pios_config_sim.h @@ -43,6 +43,7 @@ #define PIOS_INCLUDE_UDP #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_GCSRCVR #define PIOS_RCVR_MAX_CHANNELS 12 #define PIOS_RCVR_MAX_DEVS 3 diff --git a/flight/Revolution/System/pios_board_sim.c b/flight/Revolution/System/pios_board_sim.c index e54eaa8fc..07ae969fb 100644 --- a/flight/Revolution/System/pios_board_sim.c +++ b/flight/Revolution/System/pios_board_sim.c @@ -39,9 +39,7 @@ #include "manualcontrolsettings.h" #include "pios_rcvr_priv.h" - -struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]; -uint32_t pios_rcvr_max_channel; +#include "pios_gcsrcvr_priv.h" void Stack_Change() { } @@ -213,6 +211,17 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_GPS */ #endif +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uint32_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + } /** diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index c618e82ad..7e8a8c8ac 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -45,6 +45,7 @@ UAVOBJSRCFILENAMES += flightplansettings UAVOBJSRCFILENAMES += flightplanstatus UAVOBJSRCFILENAMES += flighttelemetrystats UAVOBJSRCFILENAMES += gcstelemetrystats +UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += gpsposition UAVOBJSRCFILENAMES += gpssatellites UAVOBJSRCFILENAMES += gpstime diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index be9e86b77..9ce4b9fbb 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -1754,10 +1754,13 @@ static const struct pios_ppm_cfg pios_ppm_cfg = { #endif //PPM +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "pios_gcsrcvr_priv.h" +#endif /* PIOS_INCLUDE_GCSRCVR */ + #if defined(PIOS_INCLUDE_RCVR) #include "pios_rcvr_priv.h" - -#endif +#endif /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB) #include "pios_usb_priv.h" From 9f93c9cbec1105886c01775d88da760f2e8455e7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 09:46:23 -0500 Subject: [PATCH 039/508] Get PIOS_GCSRCVR working on revo --- flight/PiOS/Boards/STM32F4xx_Revolution.h | 1 + flight/PiOS/Common/pios_gcsrcvr.c | 8 ++++---- flight/Revolution/Makefile | 1 + flight/Revolution/System/inc/pios_config.h | 2 +- 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index e342ce620..7ede8f47d 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -189,6 +189,7 @@ extern uint32_t pios_com_vcp_id; //------------------------ #define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 //------------------------- // Receiver PPM input diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c index eda2a94ed..27e13c648 100644 --- a/flight/PiOS/Common/pios_gcsrcvr.c +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -73,7 +73,7 @@ static struct pios_gcsrcvr_dev *PIOS_gcsrcvr_alloc(void) if (!gcsrcvr_dev) return(NULL); gcsrcvr_dev->magic = PIOS_GCSRCVR_DEV_MAGIC; - gcsrcvr_dev->Fresh = FALSE; + gcsrcvr_dev->Fresh = false; gcsrcvr_dev->supv_timer = 0; /* The update callback cannot receive the device pointer, so set it in a global */ @@ -94,7 +94,7 @@ static struct pios_gcsrcvr_dev *PIOS_gcsrcvr_alloc(void) gcsrcvr_dev = &pios_gcsrcvr_devs[pios_gcsrcvr_num_devs++]; gcsrcvr_dev->magic = PIOS_GCSRCVR_DEV_MAGIC; - gcsrcvr_dev->Fresh = FALSE; + gcsrcvr_dev->Fresh = false; gcsrcvr_dev->supv_timer = 0; global_gcsrcvr_dev = gcsrcvr_dev; @@ -108,7 +108,7 @@ static void gcsreceiver_updated(UAVObjEvent * ev) struct pios_gcsrcvr_dev *gcsrcvr_dev = global_gcsrcvr_dev; if (ev->obj == GCSReceiverHandle()) { GCSReceiverGet(&gcsreceiverdata); - gcsrcvr_dev->Fresh = TRUE; + gcsrcvr_dev->Fresh = true; } } @@ -163,7 +163,7 @@ static void PIOS_gcsrcvr_Supervisor(uint32_t gcsrcvr_id) { for (int32_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; i++) gcsreceiverdata.Channel[i] = PIOS_RCVR_TIMEOUT; - gcsrcvr_dev->Fresh = FALSE; + gcsrcvr_dev->Fresh = false; } #endif /* PIOS_INCLUDE_GCSRCVR */ diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index 8b0807640..55470c781 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -149,6 +149,7 @@ include $(PIOS)/STM32F4xx/library.mk SRC += $(PIOSCOMMON)/pios_mpu6000.c SRC += $(PIOSCOMMON)/pios_bma180.c SRC += $(PIOSCOMMON)/pios_etasv3.c +SRC += $(PIOSCOMMON)/pios_gcsrcvr.c SRC += $(PIOSCOMMON)/pios_l3gd20.c SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index 3129439e5..953683f51 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -82,7 +82,7 @@ //#define PIOS_INCLUDE_SBUS #define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_PWM -//#define PIOS_INCLUDE_GCSRCVR +#define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_SETTINGS #define PIOS_INCLUDE_FLASH From b11b606ddc8d092c3a5707cf321b4f247091bada Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 10:21:01 -0500 Subject: [PATCH 040/508] Fix RTH mode. Now works in simulation when GCSReceiver goes invalid. There is a small issue that when it is in RTH failsafe mode and you regain signal and your throttle is low you will disarm due to the timeout. That means you'd suddenly get it back and plumet ouf of the sky. If you are still holding throttle (which most people might do?) you will have control. The timeout needs to probably start when you regain signal. --- flight/Modules/ManualControl/manualcontrol.c | 21 +++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 16f9e664a..a6ee3b29a 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -363,14 +363,24 @@ static void manualControlTask(void *parameters) } - processFlightMode(&settings, flightMode); } - if (processFailsafe(valid_input_detected, &settings) == false) { + if (processFailsafe(cmd.Connected == MANUALCONTROLCOMMAND_CONNECTED_TRUE, &settings) == false) { // Process arming outside conditional so system will disarm when disconnected. However don't do // it when in failsafe mode + + // Only update the flight mode when we got valid data + if (cmd.Connected == MANUALCONTROLCOMMAND_CONNECTED_TRUE) + processFlightMode(&settings, flightMode); + + // However process arming all the time so it can time out processArm(&cmd, &settings); + + } else { + // In the case of failsafe don't process the channels to update the flight mode + ManualControlCommandSet(&cmd); + continue; } // Update cmd object @@ -641,6 +651,11 @@ static void setRTH(bool changed) } } +/** + * Determine based on flight settings if we should enter failsafe when there is no valid input + * it returns true when the failsafe is engaged and the informs the rest of the system not to + * use the inputs + */ static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData *settings) { static bool failsafe_enaged = false; @@ -666,9 +681,9 @@ static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData // exclude fixed wing. if (guidanceSettings.ThrottleControl == GUIDANCESETTINGS_THROTTLECONTROL_TRUE && flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { - setRTH(true); flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_RTH; + FlightStatusSet(&flightStatus); failsafe_enaged = true; } } From 70a6bf539b2ad94354dad7a6d27829ce5d1d030e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 10:30:44 -0500 Subject: [PATCH 041/508] Fix simulation implementation of pios_rcvr to match channel mappings in real firmware --- flight/PiOS.osx/osx/pios_rcvr.c | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/flight/PiOS.osx/osx/pios_rcvr.c b/flight/PiOS.osx/osx/pios_rcvr.c index 652730547..0a2a8cd87 100644 --- a/flight/PiOS.osx/osx/pios_rcvr.c +++ b/flight/PiOS.osx/osx/pios_rcvr.c @@ -80,6 +80,15 @@ out_fail: int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel) { + // Publicly facing API uses channel 1 for first channel + if(channel == 0) + return PIOS_RCVR_INVALID; + else + channel--; + + if (rcvr_id == 0) + return PIOS_RCVR_NODRIVER; + struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id]; if (!PIOS_RCVR_validate(rcvr_dev)) { From daaa66108091de2fc3ced06fd6a807d3f101d8c7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 10:50:45 -0500 Subject: [PATCH 042/508] Turned "Battery" into an optional module. It otherwise prevents flying if no voltage sensor is installed. Conflicts: shared/uavobjectdefinition/hwsettings.xml --- flight/Modules/Battery/battery.c | 31 ++++++++++++++++++----- shared/uavobjectdefinition/hwsettings.xml | 2 +- 2 files changed, 26 insertions(+), 7 deletions(-) diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index 6d072496e..aaec1d7c5 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -49,6 +49,7 @@ #include "flightbatterystate.h" #include "flightbatterysettings.h" +#include "hwsettings.h" // // Configuration @@ -58,6 +59,7 @@ // Private types // Private variables +static bool batteryEnabled = false; // Private functions static void onTimer(UAVObjEvent* ev); @@ -68,13 +70,30 @@ static void onTimer(UAVObjEvent* ev); */ int32_t BatteryInitialize(void) { - FlightBatteryStateInitialize(); - FlightBatterySettingsInitialize(); - - static UAVObjEvent ev; - memset(&ev,0,sizeof(UAVObjEvent)); - EventPeriodicCallbackCreate(&ev, onTimer, SAMPLE_PERIOD_MS / portTICK_RATE_MS); +#ifdef MODULE_BATTERY_BUILTIN + batteryEnabled = true; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_BATTERY] == HWSETTINGS_OPTIONALMODULES_ENABLED) + batteryEnabled = true; + else + batteryEnabled = false; +#endif + + if (batteryEnabled) { + FlightBatteryStateInitialize(); + FlightBatterySettingsInitialize(); + + static UAVObjEvent ev; + + memset(&ev,0,sizeof(UAVObjEvent)); + EventPeriodicCallbackCreate(&ev, onTimer, SAMPLE_PERIOD_MS / portTICK_RATE_MS); + } return 0; } diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 37c8cc9ff..a4d948767 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -18,7 +18,7 @@ - + From b45a4aa35e26e3e79085de1cd6153faf01b4952d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 4 Jun 2012 10:52:26 -0500 Subject: [PATCH 043/508] no simposix for all_flight Conflicts: Makefile --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index a8ac4ab42..dcb55416e 100644 --- a/Makefile +++ b/Makefile @@ -654,7 +654,7 @@ all_$(1)_clean: $$(addsuffix _clean, $$(filter bu_$(1), $$(BU_TARGETS))) all_$(1)_clean: $$(addsuffix _clean, $$(filter ef_$(1), $$(EF_TARGETS))) endef -ALL_BOARDS := coptercontrol pipxtreme revolution simposix +ALL_BOARDS := coptercontrol pipxtreme revolution # Friendly names of each board (used to find source tree) coptercontrol_friendly := CopterControl From ff36e880e918987f756485aaf89b95e38096d238 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 5 Jun 2012 00:53:22 -0500 Subject: [PATCH 044/508] Fix for pathcompiler and waypoint table regarding signals and new instances --- .../src/plugins/opmap/pathcompiler.cpp | 39 +++++++++++++++---- .../src/plugins/opmap/pathcompiler.h | 7 +++- .../plugins/waypointeditor/waypointtable.cpp | 29 ++++++++++++-- .../plugins/waypointeditor/waypointtable.h | 2 +- 4 files changed, 64 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index c1c7890a3..3f2a1a2b5 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -36,19 +36,25 @@ PathCompiler::PathCompiler(QObject *parent) : QObject(parent) { - Waypoint *waypoint = NULL; HomeLocation *homeLocation = NULL; + /* To catch new waypoint UAVOs */ + connect(getObjectManager(), SIGNAL(newInstance(UAVObject*)), this, SLOT(doNewInstance(UAVObject*))); + /* Connect the object updates */ - waypoint = Waypoint::GetInstance(getObjectManager()); - Q_ASSERT(waypoint); - if(waypoint) - connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV())); + int numWaypoints = getObjectManager()->getNumInstances(Waypoint::OBJID); + for (int i = 0; i < numWaypoints; i++) { + qDebug() << "Registering waypoint" << i; + Waypoint *waypoint = Waypoint::GetInstance(getObjectManager(), i); + Q_ASSERT(waypoint); + if(waypoint) + connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV(UAVObject*))); + } homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(homeLocation); if(homeLocation) - connect(homeLocation, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV())); + connect(homeLocation, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doUpdateFromUAV(UAVObject*))); } /** @@ -90,6 +96,21 @@ int PathCompiler::loadPath(QString filename) return -1; } +/** + * Called whenever a new object instance is created so we can check + * if it's a waypoint and if so connect to it + * @param [in] obj The point to the object being created + */ +void PathCompiler::doNewInstance(UAVObject* obj) +{ + Q_ASSERT(obj); + if (!obj) + return; + + if (obj->getObjID() == Waypoint::OBJID) + connect(obj, SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doUpdateFromUAV(UAVObject*))); +} + /** * add a waypoint * @param waypoint the new waypoint to add @@ -226,12 +247,16 @@ void PathCompiler::doDelAllWaypoints() * When the UAV waypoints change trigger the pathcompiler to * get the latest version and then update the visualization */ -void PathCompiler::doUpdateFromUAV() +void PathCompiler::doUpdateFromUAV(UAVObject *obj) { UAVObjectManager *objManager = getObjectManager(); if (!objManager) return; + if(obj) { + qDebug() << "Update:" << obj->getInstID(); + } + Waypoint *waypointObj = Waypoint::GetInstance(getObjectManager()); Q_ASSERT(waypointObj); if (waypointObj == NULL) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index b52ee8e89..5c05b1af1 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -96,6 +96,11 @@ public slots: * into the view. */ + /** + * Called when new instances are registered + */ + void doNewInstance(UAVObject*); + /** * add a waypoint * @param waypoint the new waypoint to add @@ -128,7 +133,7 @@ public slots: * When the UAV waypoints change trigger the pathcompiler to * get the latest version and then update the visualization */ - void doUpdateFromUAV(); + void doUpdateFromUAV(UAVObject *); }; #endif // PATHCOMPILER_H diff --git a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp index 46621952b..e0f59c60f 100644 --- a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp +++ b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp @@ -45,9 +45,18 @@ WaypointTable::WaypointTable(QObject *parent) : // Unfortunately there is no per object new instance signal yet connect(objManager, SIGNAL(newInstance(UAVObject*)), - this, SLOT(waypointsUpdated(UAVObject*))); + this, SLOT(doNewInstance(UAVObject*))); connect(waypointActiveObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(waypointsUpdated(UAVObject*))); + + int numWaypoints = objManager->getNumInstances(Waypoint::OBJID); + for (int i = 0; i < numWaypoints; i++) { + Waypoint *waypoint = Waypoint::GetInstance(objManager, i); + Q_ASSERT(waypoint); + if(waypoint) + connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(waypointsUpdated(UAVObject*))); + } + connect(waypointObj, SIGNAL(), this, SLOT(waypointsUpdated(UAVObject*))); @@ -112,6 +121,20 @@ QVariant WaypointTable::headerData(int section, Qt::Orientation orientation, int return QAbstractTableModel::headerData(section, orientation, role); } +/** + * Called for any new UAVO instance and when that is a Waypoint register + * to update the table + */ +void WaypointTable::doNewInstance(UAVObject*obj) +{ + Q_ASSERT(obj); + if (!obj) + return; + + if (obj->getObjID() == Waypoint::OBJID) + connect(obj, SIGNAL(objectUpdated(UAVObject*)),this,SLOT(waypointsUpdated(UAVObject*))); +} + /** * Called whenever the waypoints are updated to inform * the view @@ -122,7 +145,6 @@ void WaypointTable::waypointsUpdated(UAVObject *) // Currently only support adding instances which is all the UAVO manager // supports - qDebug() << "Elements before " << elementsNow << " and cached " << elements; if (elementsNow > elements) { beginInsertRows(QModelIndex(), elements, elementsNow-1); elements = elementsNow; @@ -141,8 +163,7 @@ Qt::ItemFlags WaypointTable::flags(const QModelIndex &index) const bool WaypointTable::setData ( const QModelIndex & index, const QVariant & value, int role = Qt::EditRole ) { -// if(role != Qt::EditRole) -// return false; + Q_UNUSED(role); double val = value.toDouble(); qDebug() << "New value " << val << " for column " << index.column(); diff --git a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.h b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.h index a9821e99e..cf2a5a02b 100644 --- a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.h +++ b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.h @@ -54,7 +54,7 @@ signals: protected slots: void waypointsUpdated(UAVObject *); - + void doNewInstance(UAVObject*); public slots: private: From 302575714f14e80aba1a2349ddadb77a93a147c0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 5 Jun 2012 08:30:42 -0500 Subject: [PATCH 045/508] Filter updates from the UAVOs if the waypoints haven't changed since they are set to periodic (and need to be right now until FC telemetry is fixed and sends new instances). --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 1 - .../src/plugins/opmap/pathcompiler.cpp | 22 +++++++++++++------ .../src/plugins/opmap/pathcompiler.h | 15 +++++++++---- 3 files changed, 26 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index eca598fcd..1466032e3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2237,7 +2237,6 @@ bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, doub double NED[3]; double LLA[3]; double homeLLA[3]; - UAVObject *obj; Q_ASSERT(obm != NULL); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 3f2a1a2b5..1a9564c0e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -116,7 +116,7 @@ void PathCompiler::doNewInstance(UAVObject* obj) * @param waypoint the new waypoint to add * @param position which position to insert it to, defaults to end */ -void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint waypoint, int /*position*/) +void PathCompiler::doAddWaypoint(waypoint newWaypointInternal, int /*position*/) { /* TODO: If a waypoint is inserted not at the end shift them all by one and */ /* add the data there */ @@ -124,7 +124,7 @@ void PathCompiler::doAddWaypoint(struct PathCompiler::waypoint waypoint, int /*p UAVObjectManager *objManager = getObjectManager(); // Format the data from the map into a UAVO - Waypoint::DataFields newWaypoint = InternalToUavo(waypoint); + Waypoint::DataFields newWaypoint = InternalToUavo(newWaypointInternal); // Search for any waypoints set to stop, because if they exist we // should add the waypoint immediately after that one @@ -249,6 +249,8 @@ void PathCompiler::doDelAllWaypoints() */ void PathCompiler::doUpdateFromUAV(UAVObject *obj) { + static QList previousWaypoints; + UAVObjectManager *objManager = getObjectManager(); if (!objManager) return; @@ -263,7 +265,7 @@ void PathCompiler::doUpdateFromUAV(UAVObject *obj) return; /* Get all the waypoints from the UAVO and create a representation for the visualization */ - QList waypoints; + QList waypoints; waypoints.clear(); int numWaypoints = objManager->getNumInstances(waypointObj->getObjID()); bool stopped = false; @@ -278,8 +280,14 @@ void PathCompiler::doUpdateFromUAV(UAVObject *obj) stopped = waypointData.Action == Waypoint::ACTION_STOP; } - /* Inform visualization */ - emit visualizationChanged(waypoints); + if (previousWaypoints != waypoints) { + /* Because the waypoints have to update periodically (or we miss new ones on the FC */ + /* side - needs telem fix) we want to filter updates to map that are simply periodic */ + previousWaypoints = waypoints; + + /* Inform visualization */ + emit visualizationChanged(waypoints); + } } /** @@ -292,7 +300,7 @@ struct PathCompiler::waypoint PathCompiler::UavoToInternal(Waypoint::DataFields double homeLLA[3]; double LLA[3]; double NED[3]; - struct PathCompiler::waypoint internalWaypoint; + waypoint internalWaypoint; HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(homeLocation); @@ -318,7 +326,7 @@ struct PathCompiler::waypoint PathCompiler::UavoToInternal(Waypoint::DataFields * @param internal The internal structure type * @returns The waypoint UAVO data structure */ -Waypoint::DataFields PathCompiler::InternalToUavo(struct waypoint internal) +Waypoint::DataFields PathCompiler::InternalToUavo(waypoint internal) { Waypoint::DataFields uavo; diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 5c05b1af1..4e04fcd10 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -66,7 +66,14 @@ public: int loadPath(QString filename = NULL); //! Waypoint representation that is exchanged between visualization - struct waypoint { + class waypoint { + public: + waypoint() {} + + const bool operator==(const waypoint other) { + return (other.latitude == latitude) && (other.longitude == longitude); + } + double latitude; double longitude; }; @@ -79,14 +86,14 @@ private: struct PathCompiler::waypoint UavoToInternal(Waypoint::DataFields); //! Convert a UAVO waypoint to the local structure - Waypoint::DataFields InternalToUavo(struct waypoint); + Waypoint::DataFields InternalToUavo(waypoint); signals: /** * Indicates something changed the waypoints and the map should * update the display */ - void visualizationChanged(QList); + void visualizationChanged(QList); public slots: /** @@ -106,7 +113,7 @@ public slots: * @param waypoint the new waypoint to add * @param position which position to insert it to, defaults to end */ - void doAddWaypoint(struct PathCompiler::waypoint, int position = -1); + void doAddWaypoint(waypoint, int position = -1); /** * Update waypoint From b4d59d3e3ed25add34e6519a7a7afdc14a07372c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 5 Jun 2012 10:01:12 -0500 Subject: [PATCH 046/508] Dragging and dropping waypoints now works and updates the FC immediately. --- .../src/mapwidget/waypointitem.cpp | 3 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 8 ++++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 43 ++++++++++++------- .../src/plugins/opmap/opmapgadgetwidget.h | 1 + .../src/plugins/opmap/pathcompiler.cpp | 29 +++++++++++-- .../src/plugins/opmap/pathcompiler.h | 2 +- 6 files changed, 65 insertions(+), 21 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 8f1892a61..5fd972502 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -95,6 +95,7 @@ namespace mapcontrol } void WayPointItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { + QGraphicsItem::mouseReleaseEvent(event); if(event->button()==Qt::LeftButton) { if(text) { @@ -110,8 +111,8 @@ namespace mapcontrol RefreshToolTip(); emit WPValuesChanged(this); + emit WPDropped(this); } - QGraphicsItem::mouseReleaseEvent(event); } void WayPointItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index b9bee5ce5..b8fbd70cb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -198,6 +198,7 @@ signals: * @param waypoint a pointer to this WayPoint */ void WPNumberChanged(int const& oldnumber,int const& newnumber,WayPointItem* waypoint); + /** * @brief Fired when the description, altitude or coordinates change * @@ -205,6 +206,13 @@ signals: */ void WPValuesChanged(WayPointItem* waypoint); + /** + * @brief Fired when the waypoint is dropped somewhere + * + * @param waypoint a pointer to this WayPoint + */ + void WPDropped(WayPointItem* waypoint); + }; } #endif // WAYPOINTITEM_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 1466032e3..e7381d976 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -887,26 +887,19 @@ void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumb Q_UNUSED(waypoint); } +/** + * Called whenever a waypoint item is changed on the mapcontrol. Needs to update + * the backend appropriately + */ void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) { - // qDebug("opmap: WPValuesChanged"); - switch (m_map_mode) { case Normal_MapMode: - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { // search for the waypoint in our own waypoint list and update it - if (!wp) continue; - if (!wp->map_wp_item) continue; - if (wp->map_wp_item != waypoint) continue; - // found the waypoint in our list - wp->coord = waypoint->Coord(); - wp->altitude = waypoint->Altitude(); - wp->description = waypoint->Description(); - break; - } - m_waypoint_list_mutex.unlock(); + { + // TODO: We don't parse changes in position here as it's too dense + // however a change in something like + } break; case MagicWaypoint_MapMode: @@ -2359,6 +2352,7 @@ void OPMapGadgetWidget::SetUavPic(QString UAVPic) */ void OPMapGadgetWidget::doVisualizationChanged(QList waypoints) { + disconnect(this,SLOT(WPDropped(WayPointItem*))); m_map->WPDeleteAll(); int index = 0; foreach (PathCompiler::waypoint waypoint, waypoints) { @@ -2371,5 +2365,24 @@ void OPMapGadgetWidget::doVisualizationChanged(QList way wayPointItem->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); index++; } + connect(wayPointItem, SIGNAL(WPDropped(WayPointItem*)), this, SLOT(WPDropped(WayPointItem*))); + } +} + +/** + * Called when a waypoint is dropped at a new location. Waypoint changed + * can't be used as it is updated too frequently and we don't want to + * overload the pathcompiler with unnecessary updates + */ +void OPMapGadgetWidget::WPDropped(WayPointItem *waypoint) +{ + switch (m_map_mode) + { + case Normal_MapMode: + PathCompiler::waypoint newWaypoint; + newWaypoint.latitude = waypoint->Coord().Lat(); + newWaypoint.longitude = waypoint->Coord().Lng(); + pathCompiler->doUpdateWaypoints(newWaypoint,waypoint->Number()); + break; } } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 65f4e25b9..38fa52c36 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -179,6 +179,7 @@ private slots: /** * Unused for now, hooks for future waypoint support */ + void WPDropped(WayPointItem *waypoint); void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); void WPValuesChanged(WayPointItem* waypoint); void WPInserted(int const& number, WayPointItem* waypoint); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 1a9564c0e..f8d4dca1b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -140,6 +140,7 @@ void PathCompiler::doAddWaypoint(waypoint newWaypointInternal, int /*position*/) if(waypointData.Action == Waypoint::ACTION_STOP) { waypointData.Action = Waypoint::ACTION_PATHTONEXT; waypoint->setData(waypointData); + waypoint->updated(); break; } } @@ -169,6 +170,30 @@ void PathCompiler::doAddWaypoint(waypoint newWaypointInternal, int /*position*/) } } +/** + * Update waypoint + */ +void PathCompiler::doUpdateWaypoints(PathCompiler::waypoint changedWaypoint, int position) +{ + int numWaypoints = getObjectManager()->getNumInstances(Waypoint::OBJID); + Q_ASSERT(position < numWaypoints); + if (position >= numWaypoints) + return; + + Waypoint *waypointInst = Waypoint::GetInstance(getObjectManager(), position); + Q_ASSERT(waypointInst); + + // Mirror over the updated position. We don't just use the changedWaypoint + // because things like action might need to be preserved + Waypoint::DataFields changedWaypointUAVO = InternalToUavo(changedWaypoint); + Waypoint::DataFields oldWaypointUAVO = waypointInst->getData(); + oldWaypointUAVO.Position[0] = changedWaypointUAVO.Position[0]; + oldWaypointUAVO.Position[1] = changedWaypointUAVO.Position[1]; + oldWaypointUAVO.Position[2] = changedWaypointUAVO.Position[2]; + waypointInst->setData(oldWaypointUAVO); + waypointInst->updated(); +} + /** * Delete a waypoint * @param index which waypoint to delete @@ -255,10 +280,6 @@ void PathCompiler::doUpdateFromUAV(UAVObject *obj) if (!objManager) return; - if(obj) { - qDebug() << "Update:" << obj->getInstID(); - } - Waypoint *waypointObj = Waypoint::GetInstance(getObjectManager()); Q_ASSERT(waypointObj); if (waypointObj == NULL) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 4e04fcd10..f3bdc95c4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -118,7 +118,7 @@ public slots: /** * Update waypoint */ - //void doUpdateWaypoints(struct PathCompiler::waypoint, int position); + void doUpdateWaypoints(PathCompiler::waypoint, int position); /** * Delete a waypoint From 4550eafa028c635aef5d625062528834b3eafdcd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 5 Jun 2012 17:34:44 -0500 Subject: [PATCH 047/508] Add the ability to export waypoints to an xml file --- .../uavsettingsimportexportfactory.cpp | 202 ++++++++++++++---- .../uavsettingsimportexportfactory.h | 19 +- 2 files changed, 165 insertions(+), 56 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 9c0088efa..e6476499c 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -87,6 +87,16 @@ UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject *parent): cmd->action()->setText(tr("Export UAV Data...")); ac->addAction(cmd, Core::Constants::G_HELP_HELP); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); + + ac = am->actionContainer(Core::Constants::M_FILE); + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVWaypointsExport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->action()->setText(tr("Export UAV Waypoints...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportWaypoints())); + } // Slot called by the menu manager on user action @@ -258,6 +268,7 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData // create settings and/or data elements QDomElement settings = doc.createElement("settings"); QDomElement data = doc.createElement("data"); + QDomElement waypoints = doc.createElement("waypoints"); switch (what) { @@ -271,61 +282,121 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData root.appendChild(data); root.appendChild(settings); break; + case Waypoints: + root.appendChild(waypoints); + break; } - // iterate over settings objects - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject *obj, list) { - if (((what == Settings) && obj->isSettings()) || - ((what == Data) && !obj->isSettings()) || - (what == Both)) { + switch (what) + { + case Settings: + case Data: + case Both: + { + // iterate over settings objects + QList< QList > objList = objManager->getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject *obj, list) { + if (((what == Settings) && obj->isSettings()) || + ((what == Data) && !obj->isSettings()) || + (what == Both)) { - // add each object to the XML - QDomElement o = doc.createElement("object"); - o.setAttribute("name", obj->getName()); - o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); - if (fullExport) { - QDomElement d = doc.createElement("description"); - QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); - d.appendChild(t); - o.appendChild(d); - } - - // iterate over fields - QList fieldList = obj->getFields(); - - foreach (UAVObjectField* field, fieldList) { - QDomElement f = doc.createElement("field"); - - // iterate over values - QString vals; - quint32 nelem = field->getNumElements(); - for (unsigned int n = 0; n < nelem; ++n) { - vals.append(QString("%1,").arg(field->getValue(n).toString())); - } - vals.chop(1); - - f.setAttribute("name", field->getName()); - f.setAttribute("values", vals); + // add each object to the XML + QDomElement o = doc.createElement("object"); + o.setAttribute("name", obj->getName()); + o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); if (fullExport) { - f.setAttribute("type", field->getTypeAsString()); - f.setAttribute("units", field->getUnits()); - f.setAttribute("elements", nelem); - if (field->getType() == UAVObjectField::ENUM) { - f.setAttribute("options", field->getOptions().join(",")); - } + QDomElement d = doc.createElement("description"); + QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); + d.appendChild(t); + o.appendChild(d); } - o.appendChild(f); - } - // append to the settings or data element - if (obj->isSettings()) - settings.appendChild(o); - else - data.appendChild(o); + // iterate over fields + QList fieldList = obj->getFields(); + + foreach (UAVObjectField* field, fieldList) { + QDomElement f = doc.createElement("field"); + + // iterate over values + QString vals; + quint32 nelem = field->getNumElements(); + for (unsigned int n = 0; n < nelem; ++n) { + vals.append(QString("%1,").arg(field->getValue(n).toString())); + } + vals.chop(1); + + f.setAttribute("name", field->getName()); + f.setAttribute("values", vals); + if (fullExport) { + f.setAttribute("type", field->getTypeAsString()); + f.setAttribute("units", field->getUnits()); + f.setAttribute("elements", nelem); + if (field->getType() == UAVObjectField::ENUM) { + f.setAttribute("options", field->getOptions().join(",")); + } + } + o.appendChild(f); + } + + // append to the settings or data element + if (obj->isSettings()) + settings.appendChild(o); + else + data.appendChild(o); + } } } + } + break; + case Waypoints: + { + // iterate over waypoints until the first one that is set to Stop + QList list = objManager->getObjectInstances("Waypoint"); + foreach (UAVObject *obj, list) { + // add each object to the XML + QDomElement o = doc.createElement("object"); + o.setAttribute("name", obj->getName()); + o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); + o.setAttribute("instId",QString().setNum(obj->getInstID())); + + // iterate over fields + QList fieldList = obj->getFields(); + + foreach (UAVObjectField* field, fieldList) { + QDomElement f = doc.createElement("field"); + + // iterate over values + QString vals; + quint32 nelem = field->getNumElements(); + for (unsigned int n = 0; n < nelem; ++n) { + vals.append(QString("%1,").arg(field->getValue(n).toString())); + } + vals.chop(1); + + f.setAttribute("name", field->getName()); + f.setAttribute("values", vals); + if (fullExport) { + f.setAttribute("type", field->getTypeAsString()); + f.setAttribute("units", field->getUnits()); + f.setAttribute("elements", nelem); + if (field->getType() == UAVObjectField::ENUM) { + f.setAttribute("options", field->getOptions().join(",")); + } + } + o.appendChild(f); + } + waypoints.appendChild(o); + + // If this waypoint was stop, then don't add anymore + UAVObjectField *field = obj->getField("Action"); + Q_ASSERT(field); + if(field && field->getValue().toString().compare("Stop") == 0) + break; + + } + break; + } } return doc.toString(4); @@ -423,3 +494,40 @@ void UAVSettingsImportExportFactory::exportUAVData() msgBox.setStandardButtons(QMessageBox::Ok); msgBox.exec(); } + +/** + * Slot called by the menu manager on user action + */ +void UAVSettingsImportExportFactory::exportWaypoints() +{ + + // ask for file name + QString fileName; + QString filters = tr("UAVObjects XML files (*.xml)"); + + fileName = QFileDialog::getSaveFileName(0, tr("Save waypoint File As"), "", filters); + if (fileName.isEmpty()) { + return; + } + + // generate an XML first (used for all export formats as a formatted data source) + QString xml = createXMLDocument(Waypoints, false); + + // save file + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(xml.toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("UAV Data Export"), + tr("Unable to save data: ") + fileName, + QMessageBox::Ok); + return; + } + + QMessageBox msgBox; + msgBox.setText(tr("Data saved.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); +} diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h index d2fb03952..5c9d0de37 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h @@ -34,20 +34,21 @@ class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportFactory : public QOb Q_OBJECT public: - UAVSettingsImportExportFactory(QObject *parent = 0); - ~UAVSettingsImportExportFactory(); + UAVSettingsImportExportFactory(QObject *parent = 0); + ~UAVSettingsImportExportFactory(); private: - enum storedData { Settings, Data, Both }; - QString createXMLDocument(const enum storedData, const bool fullExport); + enum storedData { Settings, Data, Waypoints, Both }; + QString createXMLDocument(const enum storedData, const bool fullExport); private slots: - void importUAVSettings(); - void exportUAVSettings(); - void exportUAVData(); + void importUAVSettings(); + void exportUAVSettings(); + void exportUAVData(); + void exportWaypoints(); signals: - void importAboutToBegin(); - void importEnded(); + void importAboutToBegin(); + void importEnded(); }; From 983153d87b400c6914a846416cdc9ee33fded185 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 5 Jun 2012 18:06:43 -0500 Subject: [PATCH 048/508] Waypoint importing now works --- .../uavsettingsimportexportfactory.cpp | 130 +++++++++++++++++- .../uavsettingsimportexportfactory.h | 2 + 2 files changed, 131 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index e6476499c..ee7880038 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -93,10 +93,19 @@ UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject *parent): "UAVSettingsImportExportPlugin.UAVWaypointsExport", QList() << Core::Constants::C_GLOBAL_ID); - cmd->action()->setText(tr("Export UAV Waypoints...")); + cmd->action()->setText(tr("Export Waypoints...")); ac->addAction(cmd, Core::Constants::G_FILE_SAVE); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportWaypoints())); + ac = am->actionContainer(Core::Constants::M_FILE); + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVWaypointsImport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->action()->setText(tr("Import Waypoints...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importWaypoints())); + } // Slot called by the menu manager on user action @@ -223,6 +232,125 @@ void UAVSettingsImportExportFactory::importUAVSettings() swui.exec(); } + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::importWaypoints() +{ + // ask for file name + QString fileName; + QString filters = tr("Waypoint XML files (*.xml)"); + fileName = QFileDialog::getOpenFileName(0, tr("Import waypoints"), "", filters); + if (fileName.isEmpty()) { + return; + } + + // Now open the file + QFile file(fileName); + QDomDocument doc("UAVObjects"); + file.open(QFile::ReadOnly|QFile::Text); + if (!doc.setContent(file.readAll())) { + QMessageBox msgBox; + msgBox.setText(tr("File Parsing Failed.")); + msgBox.setInformativeText(tr("This file is not a correct XML file")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + file.close(); + + // find the root of settings subtree + emit importAboutToBegin(); + qDebug()<<"Import about to begin"; + + QDomElement root = doc.documentElement(); + if (root.tagName() == "uavobjects") { + root = root.firstChildElement("waypoints"); + } + if (root.isNull() || (root.tagName() != "waypoints")) { + QMessageBox msgBox; + msgBox.setText(tr("Wrong file contents")); + msgBox.setInformativeText(tr("This file does not contain waypoints")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + + QDomNode node = root.firstChild(); + while (!node.isNull()) { + QDomElement e = node.toElement(); + if (e.tagName() == "object") { + + // - Read each object + QString uavObjectName = e.attribute("name"); + uint uavObjectID = e.attribute("id").toUInt(NULL,16); + uint instId = e.attribute("instId").toUInt(NULL,10); + + // Sanity Check: + UAVDataObject * obj = dynamic_cast(objManager->getObject(uavObjectName)); + if (obj == NULL) { + // This object is unknown! + qDebug() << "Object unknown:" << uavObjectName << uavObjectID; + } else { + + int numInstances = objManager->getNumInstances(obj->getObjID()); + if (instId >= numInstances) { + obj = obj->clone(instId); + objManager->registerObject(obj); + qDebug() << "Cloned new object"; + } else { + obj = dynamic_cast(objManager->getObject(uavObjectName, instId)); + Q_ASSERT(obj); + qDebug() << "Setting existing object"; + } + + // - Update each field + // - Issue and "updated" command + bool error = false; + bool setError = false; + QDomNode field = node.firstChild(); + while(!field.isNull()) { + QDomElement f = field.toElement(); + if (f.tagName() == "field") { + UAVObjectField *uavfield = obj->getField(f.attribute("name")); + if (uavfield) { + QStringList list = f.attribute("values").split(","); + if (list.length() == 1) { + if (false == uavfield->checkValue(f.attribute("values"))) { + qDebug() << "checkValue returned false on: " << uavObjectName << f.attribute("values"); + setError = true; + } else { + uavfield->setValue(f.attribute("values")); + } + } else { + // This is an enum: + int i = 0; + QStringList list = f.attribute("values").split(","); + foreach (QString element, list) { + if (false == uavfield->checkValue(element, i)) { + qDebug() << "checkValue(list) returned false on: " << uavObjectName << list; + setError = true; + } else { + uavfield->setValue(element,i); + } + i++; + } + } + } else { + error = true; + } + } + field = field.nextSibling(); + } + } + } + node = node.nextSibling(); + } + qDebug() << "End import"; +} + // Create an XML document from UAVObject database QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData what, const bool fullExport) { diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h index 5c9d0de37..a28040349 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h @@ -45,7 +45,9 @@ private slots: void importUAVSettings(); void exportUAVSettings(); void exportUAVData(); + void exportWaypoints(); + void importWaypoints(); signals: void importAboutToBegin(); void importEnded(); From 51a6370733ea7d712118e66cf481cc7bb098e092 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 7 Jun 2012 09:51:11 -0500 Subject: [PATCH 049/508] Separate GPS/UAV trails and context menu settings Conflicts: ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 251 +++++++++++++++--- .../src/plugins/opmap/opmapgadgetwidget.h | 43 ++- 2 files changed, 256 insertions(+), 38 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index e7381d976..ff2f6c14a 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -506,32 +506,64 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator()->setText(tr("UAV Trail")); + QMenu uavTrailSubMenu(tr("UAV Trail"), this); + QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this); for (int i = 0; i < uavTrailTypeAct.count(); i++) uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i)); - menu.addMenu(&uavTrailTypeSubMenu); + uavTrailSubMenu.addMenu(&uavTrailTypeSubMenu); QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this); for (int i = 0; i < uavTrailTimeAct.count(); i++) uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i)); - menu.addMenu(&uavTrailTimeSubMenu); + uavTrailSubMenu.addMenu(&uavTrailTimeSubMenu); QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this); for (int i = 0; i < uavTrailDistanceAct.count(); i++) uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i)); - menu.addMenu(&uavTrailDistanceSubMenu); + uavTrailSubMenu.addMenu(&uavTrailDistanceSubMenu); - menu.addAction(showTrailAct); + uavTrailSubMenu.addAction(showUAVtrailAct); - menu.addAction(showTrailLineAct); + uavTrailSubMenu.addAction(showUAVtrailLineAct); - menu.addAction(clearUAVtrailAct); + uavTrailSubMenu.addAction(clearUAVtrailAct); + menu.addMenu(&uavTrailSubMenu); + + // gps trails + + //menu.addSeparator()->setText(tr("GPS Trail")); + + QMenu gpsTrailSubMenu(tr("GPS Trail"), this); + + QMenu gpsTrailTypeSubMenu(tr("GPS trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->GPS->GetTrailType()) + ")", this); + for (int i = 0; i < gpsTrailTypeAct.count(); i++) + gpsTrailTypeSubMenu.addAction(gpsTrailTypeAct.at(i)); + gpsTrailSubMenu.addMenu(&gpsTrailTypeSubMenu); + + QMenu gpsTrailTimeSubMenu(tr("GPS trail time") + " (" + QString::number(m_map->GPS->TrailTime()) + " sec)", this); + for (int i = 0; i < gpsTrailTimeAct.count(); i++) + gpsTrailTimeSubMenu.addAction(gpsTrailTimeAct.at(i)); + gpsTrailSubMenu.addMenu(&gpsTrailTimeSubMenu); + + QMenu gpsTrailDistanceSubMenu(tr("GPS trail distance") + " (" + QString::number(m_map->GPS->TrailDistance()) + " meters)", this); + for (int i = 0; i < gpsTrailDistanceAct.count(); i++) + gpsTrailDistanceSubMenu.addAction(gpsTrailDistanceAct.at(i)); + gpsTrailSubMenu.addMenu(&gpsTrailDistanceSubMenu); + + gpsTrailSubMenu.addAction(showGPStrailAct); + + gpsTrailSubMenu.addAction(showGPStrailLineAct); + + gpsTrailSubMenu.addAction(clearGPStrailAct); + menu.addMenu(&gpsTrailSubMenu); // **** menu.addSeparator()->setText(tr("UAV")); menu.addAction(showUAVAct); + menu.addAction(showGPSAct); menu.addAction(followUAVpositionAct); menu.addAction(followUAVheadingAct); menu.addAction(goUAVAct); @@ -1425,12 +1457,6 @@ void OPMapGadgetWidget::createActions() showHomeAct->setChecked(true); connect(showHomeAct, SIGNAL(toggled(bool)), this, SLOT(onShowHomeAct_toggled(bool))); - showUAVAct = new QAction(tr("Show UAV"), this); - showUAVAct->setStatusTip(tr("Show/Hide the UAV")); - showUAVAct->setCheckable(true); - showUAVAct->setChecked(true); - connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); - zoomInAct = new QAction(tr("Zoom &In"), this); zoomInAct->setShortcut(Qt::Key_PageUp); zoomInAct->setStatusTip(tr("Zoom the map in")); @@ -1583,6 +1609,11 @@ void OPMapGadgetWidget::createActions() // ***** // UAV trail + showUAVAct = new QAction(tr("Show UAV"), this); + showUAVAct->setStatusTip(tr("Show/Hide the UAV")); + showUAVAct->setCheckable(true); + showUAVAct->setChecked(true); + connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); uavTrailTypeActGroup = new QActionGroup(this); connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *))); @@ -1598,24 +1629,24 @@ void OPMapGadgetWidget::createActions() uavTrailTypeAct.append(uavTrailType_act); } - showTrailAct = new QAction(tr("Show Trail dots"), this); - showTrailAct->setStatusTip(tr("Show/Hide the Trail dots")); - showTrailAct->setCheckable(true); - showTrailAct->setChecked(true); - connect(showTrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailAct_toggled(bool))); + showUAVtrailAct = new QAction(tr("Show Trail dots"), this); + showUAVtrailAct->setStatusTip(tr("Show/Hide the Trail dots")); + showUAVtrailAct->setCheckable(true); + showUAVtrailAct->setChecked(true); + connect(showUAVtrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVtrailAct_toggled(bool))); - showTrailLineAct = new QAction(tr("Show Trail lines"), this); - showTrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); - showTrailLineAct->setCheckable(true); - showTrailLineAct->setChecked(true); - connect(showTrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailLineAct_toggled(bool))); + showUAVtrailLineAct = new QAction(tr("Show Trail lines"), this); + showUAVtrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); + showUAVtrailLineAct->setCheckable(true); + showUAVtrailLineAct->setChecked(true); + connect(showUAVtrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVtrailLineAct_toggled(bool))); clearUAVtrailAct = new QAction(tr("Clear UAV trail"), this); clearUAVtrailAct->setStatusTip(tr("Clear the UAV trail")); connect(clearUAVtrailAct, SIGNAL(triggered()), this, SLOT(onClearUAVtrailAct_triggered())); uavTrailTimeActGroup = new QActionGroup(this); - connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *))); + connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVtrailTimeActGroup_triggered(QAction *))); uavTrailTimeAct.clear(); list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); for (int i = 0; i < list_size; i++) @@ -1629,7 +1660,7 @@ void OPMapGadgetWidget::createActions() } uavTrailDistanceActGroup = new QActionGroup(this); - connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *))); + connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVtrailDistanceActGroup_triggered(QAction *))); uavTrailDistanceAct.clear(); list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); for (int i = 0; i < list_size; i++) @@ -1644,6 +1675,75 @@ void OPMapGadgetWidget::createActions() // ***** + // ***** + // GPS trail + showGPSAct = new QAction(tr("Show GPS"), this); + showGPSAct->setStatusTip(tr("Show/Hide the GPS")); + showGPSAct->setCheckable(true); + showGPSAct->setChecked(false); + connect(showGPSAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPSAct_toggled(bool))); + + gpsTrailTypeActGroup = new QActionGroup(this); + connect(gpsTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTypeActGroup_triggered(QAction *))); + gpsTrailTypeAct.clear(); + QStringList gps_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); + for (int i = 0; i < gps_trail_type_list.count(); i++) + { + mapcontrol::UAVTrailType::Types gps_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(gps_trail_type_list[i]); + QAction *gpsTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(gps_trail_type), gpsTrailTypeActGroup); + gpsTrailType_act->setCheckable(true); + gpsTrailType_act->setChecked(gps_trail_type == m_map->GPS->GetTrailType()); + gpsTrailType_act->setData(i); + gpsTrailTypeAct.append(gpsTrailType_act); + } + + showGPStrailAct = new QAction(tr("Show Trail dots"), this); + showGPStrailAct->setStatusTip(tr("Show/Hide the Trail dots")); + showGPStrailAct->setCheckable(true); + showGPStrailAct->setChecked(false); + connect(showGPStrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailAct_toggled(bool))); + + showGPStrailLineAct = new QAction(tr("Show Trail lines"), this); + showGPStrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); + showGPStrailLineAct->setCheckable(true); + showGPStrailLineAct->setChecked(true); + connect(showGPStrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailLineAct_toggled(bool))); + + clearGPStrailAct = new QAction(tr("Clear GPS trail"), this); + clearGPStrailAct->setStatusTip(tr("Clear the GPS trail")); + connect(clearGPStrailAct, SIGNAL(triggered()), this, SLOT(onClearGPStrailAct_triggered())); + + gpsTrailTimeActGroup = new QActionGroup(this); + connect(gpsTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTimeActGroup_triggered(QAction *))); + gpsTrailTimeAct.clear(); + list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); + for (int i = 0; i < list_size; i++) + { + int gps_trail_time = uav_trail_time_list[i]; + QAction *gpsTrailTime_act = new QAction(QString::number(gps_trail_time) + " sec", gpsTrailTimeActGroup); + gpsTrailTime_act->setCheckable(true); + gpsTrailTime_act->setChecked(gps_trail_time == m_map->GPS->TrailTime()); + gpsTrailTime_act->setData(gps_trail_time); + gpsTrailTimeAct.append(gpsTrailTime_act); + } + + gpsTrailDistanceActGroup = new QActionGroup(this); + connect(gpsTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailDistanceActGroup_triggered(QAction *))); + gpsTrailDistanceAct.clear(); + list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); + for (int i = 0; i < list_size; i++) + { + int gps_trail_distance = uav_trail_distance_list[i]; + QAction *gpsTrailDistance_act = new QAction(QString::number(gps_trail_distance) + " meters", gpsTrailDistanceActGroup); + gpsTrailDistance_act->setCheckable(true); + gpsTrailDistance_act->setChecked(gps_trail_distance == m_map->GPS->TrailDistance()); + gpsTrailDistance_act->setData(gps_trail_distance); + gpsTrailDistanceAct.append(gpsTrailDistance_act); + } + + // ***** + + // *********************** } @@ -1829,8 +1929,60 @@ void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) setMapFollowingMode(); } +/* UAV */ +void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; -void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) + m_map->UAV->setVisible(show); +} + +void OPMapGadgetWidget::onShowUAVtrailAct_toggled(bool show) +{ + if (!m_widget || !m_map || !action) + return; + + m_map->UAV->SetShowTrail(show); +} + +void OPMapGadgetWidget::onShowUAVtrailLineAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->SetShowTrailLine(show); +} + +void OPMapGadgetWidget::onClearUAVtrailAct_triggered() +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->DeleteTrail(); +} + +void OPMapGadgetWidget::onUAVtrailTimeActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_time = (double)action->data().toInt(); + + m_map->UAV->SetTrailTime(trail_time); +} + +void OPMapGadgetWidget::onUAVtrailDistanceActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_distance = action->data().toInt(); + + m_map->UAV->SetTrailDistance(trail_distance); +} + +void OPMapGadgetWidget::onUAVtrailTypeActGroup_triggered(QAction *action) { if (!m_widget || !m_map || !action) return; @@ -1843,33 +1995,70 @@ void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) m_map->UAV->SetTrailType(uav_trail_type); } -void OPMapGadgetWidget::onClearUAVtrailAct_triggered() +/*GPS*/ +void OPMapGadgetWidget::onShowGPSAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->GPS->setVisible(show); +} + +void OPMapGadgetWidget::onShowGPStrailAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->GPS->SetShowTrail(show); +} + +void OPMapGadgetWidget::onShowGPStrailLineAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->GPS->SetShowTrailLine(show); +} + +void OPMapGadgetWidget::onClearGPStrailAct_triggered() { if (!m_widget || !m_map) return; - m_map->UAV->DeleteTrail(); m_map->GPS->DeleteTrail(); } -void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) +void OPMapGadgetWidget::onGPStrailTimeActGroup_triggered(QAction *action) { if (!m_widget || !m_map || !action) return; int trail_time = (double)action->data().toInt(); - m_map->UAV->SetTrailTime(trail_time); + m_map->GPS->SetTrailTime(trail_time); } -void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) +void OPMapGadgetWidget::onGPStrailDistanceActGroup_triggered(QAction *action) { if (!m_widget || !m_map || !action) return; int trail_distance = action->data().toInt(); - m_map->UAV->SetTrailDistance(trail_distance); + m_map->GPS->SetTrailDistance(trail_distance); +} + +void OPMapGadgetWidget::onGPStrailTypeActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_type_idx = action->data().toInt(); + + QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); + mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[trail_type_idx]); + + m_map->GPS->SetTrailType(uav_trail_type); } /** diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 38fa52c36..5c46c8831 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -197,10 +197,7 @@ private slots: // void onFindPlaceAct_triggered(); void onShowCompassAct_toggled(bool show); void onShowDiagnostics_toggled(bool show); - void onShowUAVAct_toggled(bool show); void onShowHomeAct_toggled(bool show); - void onShowTrailLineAct_toggled(bool show); - void onShowTrailAct_toggled(bool show); void onGoZoomInAct_triggered(); void onGoZoomOutAct_triggered(); void onGoMouseClickAct_triggered(); @@ -220,11 +217,29 @@ private slots: void onHomeMagicWaypointAct_triggered(); void onShowSafeAreaAct_toggled(bool show); void onSafeAreaActGroup_triggered(QAction *action); - void onUAVTrailTypeActGroup_triggered(QAction *action); + void onMaxUpdateRateActGroup_triggered(QAction *action); + + /*UAV*/ + void onShowUAVAct_toggled(bool show); + void onShowUAVtrailLineAct_toggled(bool show); + void onShowUAVtrailAct_toggled(bool show); void onClearUAVtrailAct_triggered(); void onUAVTrailTimeActGroup_triggered(QAction *action); void onUAVTrailDistanceActGroup_triggered(QAction *action); void onMaxUpdateRateActGroup_triggered(QAction *action); + void onUAVtrailTimeActGroup_triggered(QAction *action); + void onUAVtrailDistanceActGroup_triggered(QAction *action); + void onUAVtrailTypeActGroup_triggered(QAction *action); + + /*GPS*/ + void onShowGPSAct_toggled(bool show); + void onShowGPStrailLineAct_toggled(bool show); + void onShowGPStrailAct_toggled(bool show); + void onClearGPStrailAct_triggered(); + void onGPStrailTimeActGroup_triggered(QAction *action); + void onGPStrailDistanceActGroup_triggered(QAction *action); + void onGPStrailTypeActGroup_triggered(QAction *action); + private: @@ -294,7 +309,6 @@ private: QAction *showCompassAct; QAction *showDiagnostics; QAction *showHomeAct; - QAction *showUAVAct; QAction *zoomInAct; QAction *zoomOutAct; QAction *goMouseClickAct; @@ -315,16 +329,31 @@ private: QActionGroup *safeAreaActGroup; QList safeAreaAct; + // UAV + QAction *showUAVAct; QActionGroup *uavTrailTypeActGroup; QList uavTrailTypeAct; QAction *clearUAVtrailAct; QActionGroup *uavTrailTimeActGroup; - QAction *showTrailLineAct; - QAction *showTrailAct; + QAction *showUAVtrailLineAct; + QAction *showUAVtrailAct; QList uavTrailTimeAct; QActionGroup *uavTrailDistanceActGroup; QList uavTrailDistanceAct; + //GPS + QAction *showGPSAct; + QActionGroup *gpsTrailTypeActGroup; + QList gpsTrailTypeAct; + QAction *clearGPStrailAct; + QActionGroup *gpsTrailTimeActGroup; + QAction *showGPStrailLineAct; + QAction *showGPStrailAct; + QList gpsTrailTimeAct; + QActionGroup *gpsTrailDistanceActGroup; + QList gpsTrailDistanceAct; + + QActionGroup *mapModeActGroup; QList mapModeAct; From 1972470dcb926b954fe92b4715f008aa88b81c57 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 7 Jun 2012 10:07:52 -0500 Subject: [PATCH 050/508] Manualcontrolcommand needs a bit more stack space now --- flight/Modules/ManualControl/manualcontrol.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 7ab7979b3..2016d1fd0 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -54,7 +54,7 @@ #if defined(PIOS_MANUAL_STACK_SIZE) #define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE #else -#define STACK_SIZE_BYTES 1024 +#define STACK_SIZE_BYTES 1224 #endif #define TASK_PRIORITY (tskIDLE_PRIORITY+4) From 720ae43a5effdbbb1969574284769acd7c7b8a80 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 13 May 2012 16:07:14 +0200 Subject: [PATCH 051/508] Modules/GPS: Fixed NMEA parser to still update GPSPosition in case of errors, but with error flagged. --- flight/Modules/GPS/NMEA.c | 64 ++++++++++++++++++--------------------- 1 file changed, 29 insertions(+), 35 deletions(-) diff --git a/flight/Modules/GPS/NMEA.c b/flight/Modules/GPS/NMEA.c index a2b4c562c..2193ae0ce 100644 --- a/flight/Modules/GPS/NMEA.c +++ b/flight/Modules/GPS/NMEA.c @@ -58,6 +58,8 @@ #endif #define MAX_NB_PARAMS 20 + +#define NMEA_DOP_NOFIX 99.99 /* NMEA sentence parsers */ struct nmea_parser { @@ -393,19 +395,14 @@ static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, ch *gpsDataUpdated = true; // get latitude [DDMM.mmmmm] [N|S] - if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[2], param[3][0] == 'S')) { - return false; - } + if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[2], param[3][0] == 'S') || + // get longitude [dddmm.mmmmm] [E|W] + !NMEA_latlon_to_fixed_point(&GpsData->Longitude, param[4], param[5][0] == 'W') || + // check for invalid GPS fix + param[6][0] == '0') { - // get longitude [dddmm.mmmmm] [E|W] - if (!NMEA_latlon_to_fixed_point(&GpsData->Longitude, param[4], param[5][0] == 'W')) { - return false; - } - - - // check for invalid GPS fix - if (param[6][0] == '0') { - return false; + GpsData->Status = GPSPOSITION_STATUS_NOFIX; + GpsData->PDOP = GpsData->HDOP = GpsData->VDOP = NMEA_DOP_NOFIX; } // get number of satellites used in GPS solution GpsData->Satellites = atoi(param[7]); @@ -449,30 +446,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch gpst.Second = (int)hms % 100; gpst.Minute = (((int)hms - gpst.Second) / 100) % 100; gpst.Hour = (int)hms / 10000; -#endif //PIOS_GPS_MINIMAL - // don't process void sentences - if (param[2][0] == 'V') { - return false; - } - - // get latitude [DDMM.mmmmm] [N|S] - if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[3], param[4][0] == 'S')) { - return false; - } - - // get longitude [dddmm.mmmmm] [E|W] - if (!NMEA_latlon_to_fixed_point(&GpsData->Longitude, param[5], param[6][0] == 'W')) { - return false; - } - - // get speed in knots - GpsData->Groundspeed = NMEA_real_to_float(param[7]) * 0.51444f; // to m/s - - // get True course - GpsData->Heading = NMEA_real_to_float(param[8]); - -#if !defined(PIOS_GPS_MINIMAL) // get Date of fix // TODO: Should really not use a float here to be safe float date = NMEA_real_to_float(param[9]); @@ -483,6 +457,26 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch GPSTimeSet(&gpst); #endif //PIOS_GPS_MINIMAL + // don't process void sentences + if (param[2][0] == 'V') { + return false; + } + + // get latitude [DDMM.mmmmm] [N|S] + if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[3], param[4][0] == 'S') || + // get longitude [dddmm.mmmmm] [E|W] + !NMEA_latlon_to_fixed_point(&GpsData->Longitude, param[5], param[6][0] == 'W')) { + + GpsData->Status = GPSPOSITION_STATUS_NOFIX; + GpsData->PDOP = GpsData->HDOP = GpsData->VDOP = NMEA_DOP_NOFIX; + } + + // get speed in knots + GpsData->Groundspeed = NMEA_real_to_float(param[7]) * 0.51444f; // to m/s + + // get True course + GpsData->Heading = NMEA_real_to_float(param[8]); + return true; } From d54970a58a2e958694d2bc524329479995791dc2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 10:36:16 -0500 Subject: [PATCH 052/508] Fix from merging the UAV Trail option --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 11 +---------- .../src/plugins/opmap/opmapgadgetwidget.h | 5 ++--- 2 files changed, 3 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index ff2f6c14a..db3704571 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1803,15 +1803,6 @@ void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) m_map->Home->setVisible(show); } -void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->UAV->setVisible(show); - m_map->GPS->setVisible(show); -} - void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) { if (!m_widget || !m_map) @@ -1940,7 +1931,7 @@ void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) void OPMapGadgetWidget::onShowUAVtrailAct_toggled(bool show) { - if (!m_widget || !m_map || !action) + if (!m_widget || !m_map) return; m_map->UAV->SetShowTrail(show); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 5c46c8831..4f04ad5da 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -220,13 +220,12 @@ private slots: void onMaxUpdateRateActGroup_triggered(QAction *action); /*UAV*/ + void onShowTrailAct_toggled(bool show); + void onShowTrailLineAct_toggled(bool); void onShowUAVAct_toggled(bool show); void onShowUAVtrailLineAct_toggled(bool show); void onShowUAVtrailAct_toggled(bool show); void onClearUAVtrailAct_triggered(); - void onUAVTrailTimeActGroup_triggered(QAction *action); - void onUAVTrailDistanceActGroup_triggered(QAction *action); - void onMaxUpdateRateActGroup_triggered(QAction *action); void onUAVtrailTimeActGroup_triggered(QAction *action); void onUAVtrailDistanceActGroup_triggered(QAction *action); void onUAVtrailTypeActGroup_triggered(QAction *action); From 574ab3fcaa89dd023cc4581ab420b8f5e5baf082 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 6 Jun 2012 01:33:30 -0500 Subject: [PATCH 053/508] Make the VtolPathFollower an optional module Note that RTH mode right now checks that throttle control is enabled, but this should only occur if the system is a VTOL. --- flight/Modules/Battery/battery.c | 1 - flight/Modules/ManualControl/manualcontrol.c | 8 +- .../VtolPathFollower/vtolpathfollower.c | 117 ++++++++++-------- flight/Revolution/UAVObjects.inc | 2 +- .../src/plugins/uavobjects/uavobjects.pro | 4 +- shared/uavobjectdefinition/hwsettings.xml | 2 +- ...tings.xml => vtolpathfollowersettings.xml} | 4 +- 7 files changed, 75 insertions(+), 63 deletions(-) rename shared/uavobjectdefinition/{guidancesettings.xml => vtolpathfollowersettings.xml} (91%) diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index aaec1d7c5..1f9a7e720 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -74,7 +74,6 @@ int32_t BatteryInitialize(void) #ifdef MODULE_BATTERY_BUILTIN batteryEnabled = true; #else - HwSettingsInitialize(); uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; HwSettingsOptionalModulesGet(optionalModules); diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 2016d1fd0..bbe0c3465 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -40,7 +40,7 @@ #include "baroaltitude.h" #include "flighttelemetrystats.h" #include "flightstatus.h" -#include "guidancesettings.h" +#include "vtolpathfollowersettings.h" #include "manualcontrol.h" #include "manualcontrolsettings.h" #include "manualcontrolcommand.h" @@ -672,8 +672,8 @@ static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData break; case MANUALCONTROLSETTINGS_FAILSAFEBEHAVIOR_RTH: { - GuidanceSettingsData guidanceSettings; - GuidanceSettingsGet(&guidanceSettings); + VtolPathFollowerSettingsData guidanceSettings; + VtolPathFollowerSettingsGet(&guidanceSettings); FlightStatusData flightStatus; FlightStatusGet(&flightStatus); @@ -682,7 +682,7 @@ static bool processFailsafe(bool valid_input_detected, ManualControlSettingsData // already armed. It would be _really_ nice to have some indication we are actively // flying to put here. I would like to check the throttle is engaged but that would // exclude fixed wing. - if (guidanceSettings.ThrottleControl == GUIDANCESETTINGS_THROTTLECONTROL_TRUE && + if (guidanceSettings.ThrottleControl == VTOLPATHFOLLOWERSETTINGS_THROTTLECONTROL_TRUE && flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { setRTH(true); flightStatus.FlightMode = FLIGHTSTATUS_FLIGHTMODE_RTH; diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 9887089e7..66b7630a4 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -49,13 +49,14 @@ #include "vtolpathfollower.h" #include "accels.h" #include "attitudeactual.h" +#include "hwsettings.h" #include "pathdesired.h" // object that will be updated by the module #include "positionactual.h" #include "manualcontrol.h" #include "flightstatus.h" #include "gpsvelocity.h" #include "gpsposition.h" -#include "guidancesettings.h" +#include "vtolpathfollowersettings.h" #include "nedaccel.h" #include "nedposition.h" #include "stabilizationdesired.h" @@ -76,7 +77,7 @@ // Private variables static xTaskHandle pathfollowerTaskHandle; static PathDesiredData pathDesired; -static GuidanceSettingsData guidanceSettings; +static VtolPathFollowerSettingsData guidanceSettings; // Private functions static void vtolPathFollowerTask(void *parameters); @@ -86,6 +87,7 @@ static void updatePathVelocity(); static void updateEndpointVelocity(); static void updateVtolDesiredAttitude(); static float bound(float val, float min, float max); +static bool vtolpathfollower_enabled; /** * Initialise the module, called on startup @@ -93,9 +95,11 @@ static float bound(float val, float min, float max); */ int32_t VtolPathFollowerStart() { - // Start main task - xTaskCreate(vtolPathFollowerTask, (signed char *)"VtolPathFollower", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle); - TaskMonitorAdd(TASKINFO_RUNNING_PATHFOLLOWER, pathfollowerTaskHandle); + if (vtolpathfollower_enabled) { + // Start main task + xTaskCreate(vtolPathFollowerTask, (signed char *)"VtolPathFollower", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_PATHFOLLOWER, pathfollowerTaskHandle); + } return 0; } @@ -106,10 +110,19 @@ int32_t VtolPathFollowerStart() */ int32_t VtolPathFollowerInitialize() { - GuidanceSettingsInitialize(); - NedAccelInitialize(); - PathDesiredInitialize(); - VelocityDesiredInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_VTOLPATHFOLLOWER] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + VtolPathFollowerSettingsInitialize(); + NedAccelInitialize(); + PathDesiredInitialize(); + VelocityDesiredInitialize(); + vtolpathfollower_enabled = true; + } else { + vtolpathfollower_enabled = false; + } return 0; } @@ -135,10 +148,10 @@ static void vtolPathFollowerTask(void *parameters) portTickType lastUpdateTime; - GuidanceSettingsConnectCallback(SettingsUpdatedCb); + VtolPathFollowerSettingsConnectCallback(SettingsUpdatedCb); PathDesiredConnectCallback(SettingsUpdatedCb); - GuidanceSettingsGet(&guidanceSettings); + VtolPathFollowerSettingsGet(&guidanceSettings); PathDesiredGet(&pathDesired); // Main task loop @@ -253,7 +266,7 @@ static void updatePathVelocity() velocityDesired.North = progress.path_direction[0] * groundspeed; velocityDesired.East = progress.path_direction[1] * groundspeed; - float error_speed = progress.error * guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_KP]; + float error_speed = progress.error * guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KP]; float correction_velocity[2] = {progress.correction_direction[0] * error_speed, progress.correction_direction[1] * error_speed}; @@ -269,10 +282,10 @@ static void updatePathVelocity() bound(progress.fractional_progress,0,1); float downError = altitudeSetpoint - positionActual.Down; - downPosIntegral = bound(downPosIntegral + downError * dT * guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_KI], - -guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_ILIMIT], - guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_ILIMIT]); - downCommand = (downError * guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_KP] + downPosIntegral); + downPosIntegral = bound(downPosIntegral + downError * dT * guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_KI], + -guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_ILIMIT], + guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_ILIMIT]); + downCommand = (downError * guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_KP] + downPosIntegral); velocityDesired.Down = bound(downCommand, -guidanceSettings.VerticalVelMax, guidanceSettings.VerticalVelMax); @@ -305,12 +318,12 @@ void updateEndpointVelocity() float northPos = 0, eastPos = 0, downPos = 0; switch (guidanceSettings.PositionSource) { - case GUIDANCESETTINGS_POSITIONSOURCE_EKF: + case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_EKF: northPos = positionActual.North; eastPos = positionActual.East; downPos = positionActual.Down; break; - case GUIDANCESETTINGS_POSITIONSOURCE_GPSPOS: + case VTOLPATHFOLLOWERSETTINGS_POSITIONSOURCE_GPSPOS: { NEDPositionData nedPosition; NEDPositionGet(&nedPosition); @@ -326,17 +339,17 @@ void updateEndpointVelocity() // Compute desired north command northError = pathDesired.End[PATHDESIRED_END_NORTH] - northPos; - northPosIntegral = bound(northPosIntegral + northError * dT * guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_KI], - -guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_ILIMIT], - guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_ILIMIT]); - northCommand = (northError * guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_KP] + + northPosIntegral = bound(northPosIntegral + northError * dT * guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KI], + -guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_ILIMIT], + guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_ILIMIT]); + northCommand = (northError * guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KP] + northPosIntegral); eastError = pathDesired.End[PATHDESIRED_END_EAST] - eastPos; - eastPosIntegral = bound(eastPosIntegral + eastError * dT * guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_KI], - -guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_ILIMIT], - guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_ILIMIT]); - eastCommand = (eastError * guidanceSettings.HorizontalPosPI[GUIDANCESETTINGS_HORIZONTALPOSPI_KP] + + eastPosIntegral = bound(eastPosIntegral + eastError * dT * guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KI], + -guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_ILIMIT], + guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_ILIMIT]); + eastCommand = (eastError * guidanceSettings.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KP] + eastPosIntegral); // Limit the maximum velocity @@ -349,10 +362,10 @@ void updateEndpointVelocity() velocityDesired.East = eastCommand * scale; downError = pathDesired.End[PATHDESIRED_END_DOWN] - downPos; - downPosIntegral = bound(downPosIntegral + downError * dT * guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_KI], - -guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_ILIMIT], - guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_ILIMIT]); - downCommand = (downError * guidanceSettings.VerticalPosPI[GUIDANCESETTINGS_VERTICALPOSPI_KP] + downPosIntegral); + downPosIntegral = bound(downPosIntegral + downError * dT * guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_KI], + -guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_ILIMIT], + guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_ILIMIT]); + downCommand = (downError * guidanceSettings.VerticalPosPI[VTOLPATHFOLLOWERSETTINGS_VERTICALPOSPI_KP] + downPosIntegral); velocityDesired.Down = bound(downCommand, -guidanceSettings.VerticalVelMax, guidanceSettings.VerticalVelMax); @@ -376,7 +389,7 @@ static void updateVtolDesiredAttitude() StabilizationDesiredData stabDesired; AttitudeActualData attitudeActual; NedAccelData nedAccel; - GuidanceSettingsData guidanceSettings; + VtolPathFollowerSettingsData guidanceSettings; StabilizationSettingsData stabSettings; SystemSettingsData systemSettings; @@ -390,7 +403,7 @@ static void updateVtolDesiredAttitude() float downCommand; SystemSettingsGet(&systemSettings); - GuidanceSettingsGet(&guidanceSettings); + VtolPathFollowerSettingsGet(&guidanceSettings); VelocityActualGet(&velocityActual); VelocityDesiredGet(&velocityDesired); @@ -402,12 +415,12 @@ static void updateVtolDesiredAttitude() float northVel = 0, eastVel = 0, downVel = 0; switch (guidanceSettings.VelocitySource) { - case GUIDANCESETTINGS_VELOCITYSOURCE_EKF: + case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_EKF: northVel = velocityActual.North; eastVel = velocityActual.East; downVel = velocityActual.Down; break; - case GUIDANCESETTINGS_VELOCITYSOURCE_NEDVEL: + case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_NEDVEL: { GPSVelocityData gpsVelocity; GPSVelocityGet(&gpsVelocity); @@ -416,7 +429,7 @@ static void updateVtolDesiredAttitude() downVel = gpsVelocity.Down; } break; - case GUIDANCESETTINGS_VELOCITYSOURCE_GPSPOS: + case VTOLPATHFOLLOWERSETTINGS_VELOCITYSOURCE_GPSPOS: { GPSPositionData gpsPosition; GPSPositionGet(&gpsPosition); @@ -437,34 +450,34 @@ static void updateVtolDesiredAttitude() // Compute desired north command northError = velocityDesired.North - northVel; - northVelIntegral = bound(northVelIntegral + northError * dT * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KI], - -guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_ILIMIT], - guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_ILIMIT]); - northCommand = (northError * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KP] + + northVelIntegral = bound(northVelIntegral + northError * dT * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KI], + -guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_ILIMIT], + guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_ILIMIT]); + northCommand = (northError * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KP] + northVelIntegral - - nedAccel.North * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KD] + + nedAccel.North * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KD] + velocityDesired.North * guidanceSettings.VelocityFeedforward); // Compute desired east command eastError = velocityDesired.East - eastVel; - eastVelIntegral = bound(eastVelIntegral + eastError * dT * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KI], - -guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_ILIMIT], - guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_ILIMIT]); - eastCommand = (eastError * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KP] + + eastVelIntegral = bound(eastVelIntegral + eastError * dT * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KI], + -guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_ILIMIT], + guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_ILIMIT]); + eastCommand = (eastError * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KP] + eastVelIntegral - - nedAccel.East * guidanceSettings.HorizontalVelPID[GUIDANCESETTINGS_HORIZONTALVELPID_KD] + + nedAccel.East * guidanceSettings.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KD] + velocityDesired.East * guidanceSettings.VelocityFeedforward); // Compute desired down command downError = velocityDesired.Down - downVel; // Must flip this sign downError = -downError; - downVelIntegral = bound(downVelIntegral + downError * dT * guidanceSettings.VerticalVelPID[GUIDANCESETTINGS_VERTICALVELPID_KI], - -guidanceSettings.VerticalVelPID[GUIDANCESETTINGS_VERTICALVELPID_ILIMIT], - guidanceSettings.VerticalVelPID[GUIDANCESETTINGS_VERTICALVELPID_ILIMIT]); - downCommand = (downError * guidanceSettings.VerticalVelPID[GUIDANCESETTINGS_VERTICALVELPID_KP] + + downVelIntegral = bound(downVelIntegral + downError * dT * guidanceSettings.VerticalVelPID[VTOLPATHFOLLOWERSETTINGS_VERTICALVELPID_KI], + -guidanceSettings.VerticalVelPID[VTOLPATHFOLLOWERSETTINGS_VERTICALVELPID_ILIMIT], + guidanceSettings.VerticalVelPID[VTOLPATHFOLLOWERSETTINGS_VERTICALVELPID_ILIMIT]); + downCommand = (downError * guidanceSettings.VerticalVelPID[VTOLPATHFOLLOWERSETTINGS_VERTICALVELPID_KP] + downVelIntegral - - nedAccel.Down * guidanceSettings.VerticalVelPID[GUIDANCESETTINGS_VERTICALVELPID_KD]); + nedAccel.Down * guidanceSettings.VerticalVelPID[VTOLPATHFOLLOWERSETTINGS_VERTICALVELPID_KD]); stabDesired.Throttle = bound(downCommand + throttleOffset, 0, 1); @@ -477,7 +490,7 @@ static void updateVtolDesiredAttitude() eastCommand * cosf(attitudeActual.Yaw * M_PI / 180), -guidanceSettings.MaxRollPitch, guidanceSettings.MaxRollPitch); - if(guidanceSettings.ThrottleControl == GUIDANCESETTINGS_THROTTLECONTROL_FALSE) { + if(guidanceSettings.ThrottleControl == VTOLPATHFOLLOWERSETTINGS_THROTTLECONTROL_FALSE) { // For now override throttle with manual control. Disable at your risk, quad goes to China. ManualControlCommandData manualControl; ManualControlCommandGet(&manualControl); @@ -546,7 +559,7 @@ static float bound(float val, float min, float max) static void SettingsUpdatedCb(UAVObjEvent * ev) { - GuidanceSettingsGet(&guidanceSettings); + VtolPathFollowerSettingsGet(&guidanceSettings); PathDesiredGet(&pathDesired); } diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index 7e8a8c8ac..fcd19a4fa 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -50,7 +50,7 @@ UAVOBJSRCFILENAMES += gpsposition UAVOBJSRCFILENAMES += gpssatellites UAVOBJSRCFILENAMES += gpstime UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += guidancesettings +UAVOBJSRCFILENAMES += vtolpathfollowersettings UAVOBJSRCFILENAMES += homelocation UAVOBJSRCFILENAMES += i2cstats UAVOBJSRCFILENAMES += manualcontrolcommand diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index fc88bc02a..11a1410d3 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -65,7 +65,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/mixerstatus.h \ $$UAVOBJECT_SYNTHETICS/velocitydesired.h \ $$UAVOBJECT_SYNTHETICS/velocityactual.h \ - $$UAVOBJECT_SYNTHETICS/guidancesettings.h \ + $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.h \ $$UAVOBJECT_SYNTHETICS/ratedesired.h \ $$UAVOBJECT_SYNTHETICS/firmwareiapobj.h \ $$UAVOBJECT_SYNTHETICS/i2cstats.h \ @@ -133,7 +133,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/mixerstatus.cpp \ $$UAVOBJECT_SYNTHETICS/velocitydesired.cpp \ $$UAVOBJECT_SYNTHETICS/velocityactual.cpp \ - $$UAVOBJECT_SYNTHETICS/guidancesettings.cpp \ + $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.cpp \ $$UAVOBJECT_SYNTHETICS/ratedesired.cpp \ $$UAVOBJECT_SYNTHETICS/firmwareiapobj.cpp \ $$UAVOBJECT_SYNTHETICS/i2cstats.cpp \ diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index a4d948767..cdb21f6c8 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -18,7 +18,7 @@ - + diff --git a/shared/uavobjectdefinition/guidancesettings.xml b/shared/uavobjectdefinition/vtolpathfollowersettings.xml similarity index 91% rename from shared/uavobjectdefinition/guidancesettings.xml rename to shared/uavobjectdefinition/vtolpathfollowersettings.xml index 220bc9eba..f1da3e8db 100644 --- a/shared/uavobjectdefinition/guidancesettings.xml +++ b/shared/uavobjectdefinition/vtolpathfollowersettings.xml @@ -1,6 +1,6 @@ - - Settings for the @ref GuidanceModule + + Settings for the @ref VtolPathFollower module From 4c3ca17e343ce1fed79d6b6adbc478efb89b0cbf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 6 Jun 2012 01:39:45 -0500 Subject: [PATCH 054/508] Backport the fixed wing path follower --- .../fixedwingpathfollower.c | 643 ++++++++++++++++++ flight/Revolution/Makefile | 2 +- flight/Revolution/Makefile.osx | 2 +- flight/Revolution/UAVObjects.inc | 1 + .../src/plugins/uavobjects/uavobjects.pro | 2 + .../fixedwingpathfollowersettings.xml | 55 ++ .../fixedwingpathfollowerstatus.xml | 13 + 7 files changed, 716 insertions(+), 2 deletions(-) create mode 100644 flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c create mode 100644 shared/uavobjectdefinition/fixedwingpathfollowersettings.xml create mode 100644 shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml diff --git a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c new file mode 100644 index 000000000..ba22ea636 --- /dev/null +++ b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -0,0 +1,643 @@ +/** + ****************************************************************************** + * + * @file fixedwingpathfollower.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint + * and sets @ref AttitudeDesired. It only does this when the FlightMode field + * of @ref ManualControlCommand is Auto. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Input object: ActiveWaypoint + * Input object: PositionActual + * Input object: ManualControlCommand + * Output object: AttitudeDesired + * + * This module will periodically update the value of the AttitudeDesired object. + * + * The module executes in its own thread in this example. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "openpilot.h" +#include "paths.h" + +#include "accels.h" +#include "hwsettings.h" +#include "attitudeactual.h" +#include "pathdesired.h" // object that will be updated by the module +#include "positionactual.h" +#include "manualcontrol.h" +#include "flightstatus.h" +#include "pathstatus.h" +#include "baroairspeed.h" +#include "gpsvelocity.h" +#include "gpsposition.h" +#include "fixedwingpathfollowersettings.h" +#include "fixedwingpathfollowerstatus.h" +#include "homelocation.h" +#include "nedposition.h" +#include "stabilizationdesired.h" +#include "stabilizationsettings.h" +#include "systemsettings.h" +#include "velocitydesired.h" +#include "velocityactual.h" +#include "CoordinateConversions.h" + +// Private constants +#define MAX_QUEUE_SIZE 4 +#define STACK_SIZE_BYTES 1548 +#define TASK_PRIORITY (tskIDLE_PRIORITY+2) +#define F_PI 3.14159265358979323846f +#define RAD2DEG (180.0f/F_PI) +#define DEG2RAD (F_PI/180.0f) +#define GEE 9.81f +// Private types + +// Private variables +static bool followerEnabled = false; +static xTaskHandle pathfollowerTaskHandle; +static PathDesiredData pathDesired; +static PathStatusData pathStatus; +static FixedWingPathFollowerSettingsData fixedwingpathfollowerSettings; + +// Private functions +static void pathfollowerTask(void *parameters); +static void SettingsUpdatedCb(UAVObjEvent * ev); +static void updatePathVelocity(); +static uint8_t updateFixedDesiredAttitude(); +static void updateFixedAttitude(); +static void baroAirspeedUpdatedCb(UAVObjEvent * ev); +static float bound(float val, float min, float max); + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t FixedWingPathFollowerStart() +{ + if (followerEnabled) { + // Start main task + xTaskCreate(pathfollowerTask, (signed char *)"PathFollower", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_PATHFOLLOWER, pathfollowerTaskHandle); + } + + return 0; +} + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t FixedWingPathFollowerInitialize() +{ + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + HwSettingsOptionalModulesGet(optionalModules); + if (optionalModules[HWSETTINGS_OPTIONALMODULES_FIXEDWINGPATHFOLLOWER] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + followerEnabled = true; + FixedWingPathFollowerSettingsInitialize(); + FixedWingPathFollowerStatusInitialize(); + PathDesiredInitialize(); + PathStatusInitialize(); + VelocityDesiredInitialize(); + BaroAirspeedInitialize(); + } else { + followerEnabled = false; + } + return 0; +} +MODULE_INITCALL(FixedWingPathFollowerInitialize, FixedWingPathFollowerStart) + +static float northVelIntegral = 0; +static float eastVelIntegral = 0; +static float downVelIntegral = 0; + +static float courseIntegral = 0; +static float speedIntegral = 0; +static float accelIntegral = 0; +static float powerIntegral = 0; + +// correct speed by measured airspeed +static float baroAirspeedBias = 0; + +/** + * Module thread, should not return. + */ +static void pathfollowerTask(void *parameters) +{ + SystemSettingsData systemSettings; + FlightStatusData flightStatus; + + portTickType lastUpdateTime; + + BaroAirspeedConnectCallback(baroAirspeedUpdatedCb); + FixedWingPathFollowerSettingsConnectCallback(SettingsUpdatedCb); + PathDesiredConnectCallback(SettingsUpdatedCb); + + FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); + PathDesiredGet(&pathDesired); + + // Main task loop + lastUpdateTime = xTaskGetTickCount(); + while (1) { + + // Conditions when this runs: + // 1. Must have FixedWing type airframe + // 2. Flight mode is PositionHold and PathDesired.Mode is Endpoint OR + // FlightMode is PathPlanner and PathDesired.Mode is Endpoint or Path + + SystemSettingsGet(&systemSettings); + if ( (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWING) && + (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGELEVON) && + (systemSettings.AirframeType != SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGVTAIL) ) + { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_WARNING); + vTaskDelay(1000); + continue; + } + + // Continue collecting data if not enough time + vTaskDelayUntil(&lastUpdateTime, fixedwingpathfollowerSettings.UpdatePeriod / portTICK_RATE_MS); + + + FlightStatusGet(&flightStatus); + PathStatusGet(&pathStatus); + + uint8_t result; + // Check the combinations of flightmode and pathdesired mode + switch(flightStatus.FlightMode) { + case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: + case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: + if (pathDesired.Mode == PATHDESIRED_MODE_FLYENDPOINT) { + updatePathVelocity(); + result = updateFixedDesiredAttitude(); + if (result) { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); + } else { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_WARNING); + } + } else { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); + } + break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + pathStatus.UID = pathDesired.UID; + pathStatus.Status = PATHSTATUS_STATUS_INPROGRESS; + switch(pathDesired.Mode) { + case PATHDESIRED_MODE_FLYENDPOINT: + case PATHDESIRED_MODE_FLYVECTOR: + case PATHDESIRED_MODE_FLYCIRCLERIGHT: + case PATHDESIRED_MODE_FLYCIRCLELEFT: + updatePathVelocity(); + result = updateFixedDesiredAttitude(); + if (result) { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); + } else { + pathStatus.Status = PATHSTATUS_STATUS_CRITICAL; + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_WARNING); + } + break; + case PATHDESIRED_MODE_FIXEDATTITUDE: + updateFixedAttitude(pathDesired.ModeParameters); + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); + break; + case PATHDESIRED_MODE_DISARMALARM: + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_CRITICAL); + break; + default: + pathStatus.Status = PATHSTATUS_STATUS_CRITICAL; + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); + break; + } + break; + default: + // Be cleaner and get rid of global variables + northVelIntegral = 0; + eastVelIntegral = 0; + downVelIntegral = 0; + courseIntegral = 0; + speedIntegral = 0; + accelIntegral = 0; + powerIntegral = 0; + + break; + } + PathStatusSet(&pathStatus); + } +} + +/** + * Compute desired velocity from the current position and path + * + * Takes in @ref PositionActual and compares it to @ref PathDesired + * and computes @ref VelocityDesired + */ +static void updatePathVelocity() +{ + PositionActualData positionActual; + PositionActualGet(&positionActual); + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + + // look ahead fixedwingpathfollowerSettings.CourseFeedForward seconds + float cur[3] = {positionActual.North + (velocityActual.North * fixedwingpathfollowerSettings.CourseFeedForward), + positionActual.East + (velocityActual.East * fixedwingpathfollowerSettings.CourseFeedForward), + positionActual.Down + (velocityActual.Down * fixedwingpathfollowerSettings.CourseFeedForward) + }; + struct path_status progress; + + path_progress(pathDesired.Start, pathDesired.End, cur, &progress, pathDesired.Mode); + + float groundspeed; + float altitudeSetpoint; + switch (pathDesired.Mode) { + case PATHDESIRED_MODE_FLYCIRCLERIGHT: + case PATHDESIRED_MODE_DRIVECIRCLERIGHT: + case PATHDESIRED_MODE_FLYCIRCLELEFT: + case PATHDESIRED_MODE_DRIVECIRCLELEFT: + groundspeed = pathDesired.EndingVelocity; + altitudeSetpoint = pathDesired.End[2]; + break; + case PATHDESIRED_MODE_FLYENDPOINT: + case PATHDESIRED_MODE_DRIVEENDPOINT: + case PATHDESIRED_MODE_FLYVECTOR: + case PATHDESIRED_MODE_DRIVEVECTOR: + default: + groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * + bound(progress.fractional_progress,0,1); + altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * + bound(progress.fractional_progress,0,1); + break; + } + + // calculate velocity - can be zero if waypoints are too close + VelocityDesiredData velocityDesired; + velocityDesired.North = progress.path_direction[0] * bound(groundspeed,1e-6,groundspeed); + velocityDesired.East = progress.path_direction[1] * bound(groundspeed,1e-6,groundspeed); + + float error_speed = progress.error * fixedwingpathfollowerSettings.HorizontalPosP; + + // calculate correction - can also be zero if correction vector is 0 or no error present + velocityDesired.North += progress.correction_direction[0] * error_speed; + velocityDesired.East += progress.correction_direction[1] * error_speed; + + float downError = altitudeSetpoint - positionActual.Down; + velocityDesired.Down = downError * fixedwingpathfollowerSettings.VerticalPosP; + + // update pathstatus + pathStatus.error = progress.error; + pathStatus.fractional_progress = progress.fractional_progress; + + VelocityDesiredSet(&velocityDesired); +} + + +/** + * Compute desired attitude from a fixed preset + * + */ +static void updateFixedAttitude(float* attitude) +{ + StabilizationDesiredData stabDesired; + StabilizationDesiredGet(&stabDesired); + stabDesired.Roll = attitude[0]; + stabDesired.Pitch = attitude[1]; + stabDesired.Yaw = attitude[2]; + stabDesired.Throttle = attitude[3]; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + StabilizationDesiredSet(&stabDesired); +} + +/** + * Compute desired attitude from the desired velocity + * + * Takes in @ref NedActual which has the acceleration in the + * NED frame as the feedback term and then compares the + * @ref VelocityActual against the @ref VelocityDesired + */ +static uint8_t updateFixedDesiredAttitude() +{ + + uint8_t result = 1; + + float dT = fixedwingpathfollowerSettings.UpdatePeriod / 1000.0f; + + VelocityDesiredData velocityDesired; + VelocityActualData velocityActual; + StabilizationDesiredData stabDesired; + AttitudeActualData attitudeActual; + AccelsData accels; + FixedWingPathFollowerSettingsData fixedwingpathfollowerSettings; + StabilizationSettingsData stabSettings; + FixedWingPathFollowerStatusData fixedwingpathfollowerStatus; + + float groundspeedActual; + float groundspeedDesired; + float airspeedActual; + float airspeedDesired; + float speedError; + float accelActual; + float accelDesired; + float accelError; + float accelCommand; + + float pitchCommand; + + float climbspeedDesired; + float climbspeedError; + float powerError; + float powerCommand; + + float courseError; + float courseCommand; + + FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); + + FixedWingPathFollowerStatusGet(&fixedwingpathfollowerStatus); + + VelocityActualGet(&velocityActual); + VelocityDesiredGet(&velocityDesired); + StabilizationDesiredGet(&stabDesired); + VelocityDesiredGet(&velocityDesired); + AttitudeActualGet(&attitudeActual); + AccelsGet(&accels); + StabilizationSettingsGet(&stabSettings); + + + /** + * Compute speed error (required for throttle and pitch) + */ + + // Current ground speed + groundspeedActual = sqrtf( velocityActual.East*velocityActual.East + velocityActual.North*velocityActual.North ); + airspeedActual = groundspeedActual + baroAirspeedBias; + + // Desired ground speed + groundspeedDesired = sqrtf(velocityDesired.North*velocityDesired.North + velocityDesired.East*velocityDesired.East); + airspeedDesired = bound( groundspeedDesired + baroAirspeedBias, + fixedwingpathfollowerSettings.AirSpeedMin, + fixedwingpathfollowerSettings.AirSpeedMax); + + // Airspeed error + speedError = airspeedDesired - ( airspeedActual ); + // Vertical error + climbspeedDesired = bound ( + velocityDesired.Down, + -fixedwingpathfollowerSettings.VerticalVelMax, + fixedwingpathfollowerSettings.VerticalVelMax); + climbspeedError = climbspeedDesired - velocityActual.Down; + + // Error condition: wind speed is higher than maximum allowed speed. We are forced backwards! + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_WIND] = 0; + if (groundspeedDesired - baroAirspeedBias <= 0 ) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_WIND] = 1; + result = 0; + } + // Error condition: plane too slow or too fast + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_HIGHSPEED] = 0; + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_LOWSPEED] = 0; + if ( airspeedActual > fixedwingpathfollowerSettings.AirSpeedMax * 1.2f) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_HIGHSPEED] = 1; + result = 0; + } + if (airspeedActual < fixedwingpathfollowerSettings.AirSpeedMin * 0.8f) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_LOWSPEED] = 1; + result = 0; + } + + if (airspeedActual<1e-6) { + // prevent division by zero, abort without controlling anything. This guidance mode is not suited for takeoff or touchdown, or handling stationary planes + // also we cannot handle planes flying backwards, lets just wait until the nose drops + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_LOWSPEED] = 1; + return 0; + } + + /** + * Compute desired throttle command + */ + // compute desired power + powerError = -climbspeedError + + bound ( + (speedError/airspeedActual) * fixedwingpathfollowerSettings.AirspeedToVerticalCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_AIRSPEEDTOVERTICALCROSSFEED_KP], + -fixedwingpathfollowerSettings.AirspeedToVerticalCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_AIRSPEEDTOVERTICALCROSSFEED_MAX], + fixedwingpathfollowerSettings.AirspeedToVerticalCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_AIRSPEEDTOVERTICALCROSSFEED_MAX] + ); + powerIntegral = bound(powerIntegral + powerError * dT * fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_KI], + -fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT], + fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT]); + powerCommand = (powerError * fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_KP] + + powerIntegral) + fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_NEUTRAL]; + + // prevent integral running out of bounds + if ( powerCommand > fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MAX]) { + powerIntegral = bound( + powerIntegral - + ( powerCommand + - fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MAX]), + -fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT], + fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT]); + powerCommand = fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MAX]; + } + if ( powerCommand < fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MIN]) { + powerIntegral = bound( + powerIntegral - + ( powerCommand + - fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MIN]), + -fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT], + fixedwingpathfollowerSettings.PowerPI[FIXEDWINGPATHFOLLOWERSETTINGS_POWERPI_ILIMIT]); + powerCommand = fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MIN]; + } + + fixedwingpathfollowerStatus.E[FIXEDWINGPATHFOLLOWERSTATUS_E_POWER] = powerError; + fixedwingpathfollowerStatus.A[FIXEDWINGPATHFOLLOWERSTATUS_A_POWER] = powerIntegral; + fixedwingpathfollowerStatus.C[FIXEDWINGPATHFOLLOWERSTATUS_C_POWER] = powerCommand; + + // set throttle + stabDesired.Throttle = powerCommand; + + // Error condition: plane cannot hold altitude at current speed. + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_LOWPOWER] = 0; + if ( + powerCommand == fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MAX] // throttle at maximum + && velocityActual.Down > 0 // we ARE going down + && climbspeedDesired < 0 // we WANT to go up + && speedError > 0 // we are too slow already + ) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_LOWPOWER] = 1; + result = 0; + } + // Error condition: plane keeps climbing despite minimum throttle (opposite of above) + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_HIGHPOWER] = 0; + if ( + powerCommand == fixedwingpathfollowerSettings.ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGS_THROTTLELIMIT_MIN] // throttle at minimum + && velocityActual.Down < 0 // we ARE going up + && climbspeedDesired > 0 // we WANT to go down + && speedError < 0 // we are too fast already + ) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_HIGHPOWER] = 1; + result = 0; + } + + + /** + * Compute desired pitch command + */ + // compute desired acceleration + accelDesired = bound( (speedError/airspeedActual) * fixedwingpathfollowerSettings.SpeedP[FIXEDWINGPATHFOLLOWERSETTINGS_SPEEDP_KP], + -fixedwingpathfollowerSettings.SpeedP[FIXEDWINGPATHFOLLOWERSETTINGS_SPEEDP_MAX], + fixedwingpathfollowerSettings.SpeedP[FIXEDWINGPATHFOLLOWERSETTINGS_SPEEDP_MAX]); + + fixedwingpathfollowerStatus.E[FIXEDWINGPATHFOLLOWERSTATUS_E_SPEED] = (speedError/airspeedActual); + fixedwingpathfollowerStatus.A[FIXEDWINGPATHFOLLOWERSTATUS_A_SPEED] = 0.0f; + fixedwingpathfollowerStatus.C[FIXEDWINGPATHFOLLOWERSTATUS_C_SPEED] = accelDesired; + + // exclude gravity from acceleration. If the aicraft is flying at high pitch, it fights gravity without getting faster + accelActual = accels.x - (sinf( DEG2RAD * attitudeActual.Pitch) * GEE); + + accelError = accelDesired - accelActual; + accelIntegral = bound(accelIntegral + accelError * dT * fixedwingpathfollowerSettings.AccelPI[FIXEDWINGPATHFOLLOWERSETTINGS_ACCELPI_KI], + -fixedwingpathfollowerSettings.AccelPI[FIXEDWINGPATHFOLLOWERSETTINGS_ACCELPI_ILIMIT], + fixedwingpathfollowerSettings.AccelPI[FIXEDWINGPATHFOLLOWERSETTINGS_ACCELPI_ILIMIT]); + accelCommand = (accelError * fixedwingpathfollowerSettings.AccelPI[FIXEDWINGPATHFOLLOWERSETTINGS_ACCELPI_KP] + + accelIntegral); + + fixedwingpathfollowerStatus.E[FIXEDWINGPATHFOLLOWERSTATUS_E_ACCEL] = accelError; + fixedwingpathfollowerStatus.A[FIXEDWINGPATHFOLLOWERSTATUS_A_ACCEL] = accelIntegral; + fixedwingpathfollowerStatus.C[FIXEDWINGPATHFOLLOWERSTATUS_C_ACCEL] = accelCommand; + + // compute desired pitch + pitchCommand= -accelCommand + bound ( (-climbspeedError/airspeedActual) * fixedwingpathfollowerSettings.VerticalToPitchCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_VERTICALTOPITCHCROSSFEED_KP], + -fixedwingpathfollowerSettings.VerticalToPitchCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_VERTICALTOPITCHCROSSFEED_MAX], + fixedwingpathfollowerSettings.VerticalToPitchCrossFeed[FIXEDWINGPATHFOLLOWERSETTINGS_VERTICALTOPITCHCROSSFEED_MAX] + ); + stabDesired.Pitch = bound(fixedwingpathfollowerSettings.PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGS_PITCHLIMIT_NEUTRAL] + + pitchCommand, + fixedwingpathfollowerSettings.PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGS_PITCHLIMIT_MIN], + fixedwingpathfollowerSettings.PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGS_PITCHLIMIT_MAX]); + + // Error condition: high speed dive + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_PITCHCONTROL] = 0; + if ( + pitchCommand == fixedwingpathfollowerSettings.PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGS_PITCHLIMIT_MAX] // pitch demand is full up + && velocityActual.Down > 0 // we ARE going down + && climbspeedDesired < 0 // we WANT to go up + && speedError < 0 // we are too fast already + ) { + fixedwingpathfollowerStatus.Errors[FIXEDWINGPATHFOLLOWERSTATUS_ERRORS_PITCHCONTROL] = 1; + result = 0; + } + + + /** + * Compute desired roll command + */ + if (groundspeedDesired> 1e-6) { + courseError = RAD2DEG * (atan2f(velocityDesired.East,velocityDesired.North) - atan2f(velocityActual.East,velocityActual.North)); + } else { + // if we are not supposed to move, keep going wherever we are now. Don't make things worse by changing direction. + courseError = 0; + } + + if (courseError<-180.0f) courseError+=360.0f; + if (courseError>180.0f) courseError-=360.0f; + + courseIntegral = bound(courseIntegral + courseError * dT * fixedwingpathfollowerSettings.CoursePI[FIXEDWINGPATHFOLLOWERSETTINGS_COURSEPI_KI], + -fixedwingpathfollowerSettings.CoursePI[FIXEDWINGPATHFOLLOWERSETTINGS_COURSEPI_ILIMIT], + fixedwingpathfollowerSettings.CoursePI[FIXEDWINGPATHFOLLOWERSETTINGS_COURSEPI_ILIMIT]); + courseCommand = (courseError * fixedwingpathfollowerSettings.CoursePI[FIXEDWINGPATHFOLLOWERSETTINGS_COURSEPI_KP] + + courseIntegral); + + fixedwingpathfollowerStatus.E[FIXEDWINGPATHFOLLOWERSTATUS_E_COURSE] = courseError; + fixedwingpathfollowerStatus.A[FIXEDWINGPATHFOLLOWERSTATUS_A_COURSE] = courseIntegral; + fixedwingpathfollowerStatus.C[FIXEDWINGPATHFOLLOWERSTATUS_C_COURSE] = courseCommand; + + stabDesired.Roll = bound( fixedwingpathfollowerSettings.RollLimit[FIXEDWINGPATHFOLLOWERSETTINGS_ROLLLIMIT_NEUTRAL] + + courseCommand, + fixedwingpathfollowerSettings.RollLimit[FIXEDWINGPATHFOLLOWERSETTINGS_ROLLLIMIT_MIN], + fixedwingpathfollowerSettings.RollLimit[FIXEDWINGPATHFOLLOWERSETTINGS_ROLLLIMIT_MAX] ); + + // TODO: find a check to determine loss of directional control. Likely needs some check of derivative + + + /** + * Compute desired yaw command + */ + // TODO implement raw control mode for yaw and base on Accels.X + stabDesired.Yaw = 0; + + + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_NONE; + + StabilizationDesiredSet(&stabDesired); + + FixedWingPathFollowerStatusSet(&fixedwingpathfollowerStatus); + + return result; +} + + +/** + * Bound input value between limits + */ +static float bound(float val, float min, float max) +{ + if (val < min) { + val = min; + } else if (val > max) { + val = max; + } + return val; +} + +static void SettingsUpdatedCb(UAVObjEvent * ev) +{ + FixedWingPathFollowerSettingsGet(&fixedwingpathfollowerSettings); + PathDesiredGet(&pathDesired); +} + +static void baroAirspeedUpdatedCb(UAVObjEvent * ev) +{ + + BaroAirspeedData baroAirspeed; + VelocityActualData velocityActual; + + BaroAirspeedGet(&baroAirspeed); + if (baroAirspeed.Connected != BAROAIRSPEED_CONNECTED_TRUE) { + baroAirspeedBias = 0; + } else { + VelocityActualGet(&velocityActual); + float groundspeed = sqrtf(velocityActual.East*velocityActual.East + velocityActual.North*velocityActual.North ); + + baroAirspeedBias = baroAirspeed.Airspeed - groundspeed; + } + +} diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index 55470c781..88d154ba5 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -53,7 +53,7 @@ MODULES = Sensors Attitude/revolution ManualControl Stabilization Actuator MODULES += Battery MODULES += Altitude/revolution GPS FirmwareIAP MODULES += Airspeed/revolution -MODULES += AltitudeHold VtolPathFollower PathPlanner +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += CameraStab MODULES += OveroSync MODULES += Telemetry diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index bc1f50988..91bddb9a5 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -54,7 +54,7 @@ USE_THUMB_MODE = YES # List of modules to include MODULES += Actuator ManualControl Stabilization -MODULES += AltitudeHold VtolPathFollower PathPlanner +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += Attitude/revolution #MODULES += OveroSync/simulated diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index fcd19a4fa..00ef1fbe8 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -37,6 +37,7 @@ UAVOBJSRCFILENAMES += accels UAVOBJSRCFILENAMES += magnetometer UAVOBJSRCFILENAMES += baroaltitude UAVOBJSRCFILENAMES += baroairspeed +UAVOBJSRCFILENAMES += fixedwingpathfollowersettings UAVOBJSRCFILENAMES += flightbatterysettings UAVOBJSRCFILENAMES += firmwareiapobj UAVOBJSRCFILENAMES += flightbatterystate diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 11a1410d3..f639f0631 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -40,6 +40,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/magnetometer.h \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ + $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.h \ $$UAVOBJECT_SYNTHETICS/systemstats.h \ $$UAVOBJECT_SYNTHETICS/systemalarms.h \ $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ @@ -120,6 +121,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/actuatorsettings.cpp \ $$UAVOBJECT_SYNTHETICS/actuatordesired.cpp \ $$UAVOBJECT_SYNTHETICS/actuatorcommand.cpp \ + $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.cpp \ $$UAVOBJECT_SYNTHETICS/gpsposition.cpp \ $$UAVOBJECT_SYNTHETICS/gpstime.cpp \ $$UAVOBJECT_SYNTHETICS/gpssatellites.cpp \ diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml new file mode 100644 index 000000000..667153a3c --- /dev/null +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -0,0 +1,55 @@ + + + Settings for the @ref FixedWingPathFollowerModule + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml new file mode 100644 index 000000000..b384434ca --- /dev/null +++ b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml @@ -0,0 +1,13 @@ + + + Object Storing Debugging Information on PID internals + + + + + + + + + + From a28aac47b599c157cb243607445057800214b5e7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 6 Jun 2012 01:49:42 -0500 Subject: [PATCH 055/508] Strip down FW navigation to be supported by my simple scheme --- .../fixedwingpathfollower.c | 78 ++++--------------- flight/Revolution/UAVObjects.inc | 1 + 2 files changed, 14 insertions(+), 65 deletions(-) diff --git a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c index ba22ea636..2b26614bd 100644 --- a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -53,7 +53,6 @@ #include "positionactual.h" #include "manualcontrol.h" #include "flightstatus.h" -#include "pathstatus.h" #include "baroairspeed.h" #include "gpsvelocity.h" #include "gpsposition.h" @@ -82,7 +81,6 @@ static bool followerEnabled = false; static xTaskHandle pathfollowerTaskHandle; static PathDesiredData pathDesired; -static PathStatusData pathStatus; static FixedWingPathFollowerSettingsData fixedwingpathfollowerSettings; // Private functions @@ -90,7 +88,6 @@ static void pathfollowerTask(void *parameters); static void SettingsUpdatedCb(UAVObjEvent * ev); static void updatePathVelocity(); static uint8_t updateFixedDesiredAttitude(); -static void updateFixedAttitude(); static void baroAirspeedUpdatedCb(UAVObjEvent * ev); static float bound(float val, float min, float max); @@ -123,7 +120,6 @@ int32_t FixedWingPathFollowerInitialize() FixedWingPathFollowerSettingsInitialize(); FixedWingPathFollowerStatusInitialize(); PathDesiredInitialize(); - PathStatusInitialize(); VelocityDesiredInitialize(); BaroAirspeedInitialize(); } else { @@ -184,16 +180,14 @@ static void pathfollowerTask(void *parameters) // Continue collecting data if not enough time vTaskDelayUntil(&lastUpdateTime, fixedwingpathfollowerSettings.UpdatePeriod / portTICK_RATE_MS); - FlightStatusGet(&flightStatus); - PathStatusGet(&pathStatus); uint8_t result; // Check the combinations of flightmode and pathdesired mode switch(flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: - case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: - if (pathDesired.Mode == PATHDESIRED_MODE_FLYENDPOINT) { + case FLIGHTSTATUS_FLIGHTMODE_RTH: + if (pathDesired.Mode == PATHDESIRED_MODE_ENDPOINT) { updatePathVelocity(); result = updateFixedDesiredAttitude(); if (result) { @@ -206,31 +200,18 @@ static void pathfollowerTask(void *parameters) } break; case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: - pathStatus.UID = pathDesired.UID; - pathStatus.Status = PATHSTATUS_STATUS_INPROGRESS; switch(pathDesired.Mode) { - case PATHDESIRED_MODE_FLYENDPOINT: - case PATHDESIRED_MODE_FLYVECTOR: - case PATHDESIRED_MODE_FLYCIRCLERIGHT: - case PATHDESIRED_MODE_FLYCIRCLELEFT: + case PATHDESIRED_MODE_PATH: + case PATHDESIRED_MODE_ENDPOINT: updatePathVelocity(); result = updateFixedDesiredAttitude(); if (result) { AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); } else { - pathStatus.Status = PATHSTATUS_STATUS_CRITICAL; AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_WARNING); } break; - case PATHDESIRED_MODE_FIXEDATTITUDE: - updateFixedAttitude(pathDesired.ModeParameters); - AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); - break; - case PATHDESIRED_MODE_DISARMALARM: - AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_CRITICAL); - break; default: - pathStatus.Status = PATHSTATUS_STATUS_CRITICAL; AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); break; } @@ -247,7 +228,6 @@ static void pathfollowerTask(void *parameters) break; } - PathStatusSet(&pathStatus); } } @@ -271,28 +251,19 @@ static void updatePathVelocity() }; struct path_status progress; - path_progress(pathDesired.Start, pathDesired.End, cur, &progress, pathDesired.Mode); + path_progress(pathDesired.Start, pathDesired.End, cur, &progress); float groundspeed; float altitudeSetpoint; switch (pathDesired.Mode) { - case PATHDESIRED_MODE_FLYCIRCLERIGHT: - case PATHDESIRED_MODE_DRIVECIRCLERIGHT: - case PATHDESIRED_MODE_FLYCIRCLELEFT: - case PATHDESIRED_MODE_DRIVECIRCLELEFT: - groundspeed = pathDesired.EndingVelocity; - altitudeSetpoint = pathDesired.End[2]; - break; - case PATHDESIRED_MODE_FLYENDPOINT: - case PATHDESIRED_MODE_DRIVEENDPOINT: - case PATHDESIRED_MODE_FLYVECTOR: - case PATHDESIRED_MODE_DRIVEVECTOR: - default: - groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * - bound(progress.fractional_progress,0,1); - altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * - bound(progress.fractional_progress,0,1); - break; + case PATHDESIRED_MODE_PATH: + case PATHDESIRED_MODE_ENDPOINT: + default: + groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * + bound(progress.fractional_progress,0,1); + altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * + bound(progress.fractional_progress,0,1); + break; } // calculate velocity - can be zero if waypoints are too close @@ -309,32 +280,9 @@ static void updatePathVelocity() float downError = altitudeSetpoint - positionActual.Down; velocityDesired.Down = downError * fixedwingpathfollowerSettings.VerticalPosP; - // update pathstatus - pathStatus.error = progress.error; - pathStatus.fractional_progress = progress.fractional_progress; - VelocityDesiredSet(&velocityDesired); } - -/** - * Compute desired attitude from a fixed preset - * - */ -static void updateFixedAttitude(float* attitude) -{ - StabilizationDesiredData stabDesired; - StabilizationDesiredGet(&stabDesired); - stabDesired.Roll = attitude[0]; - stabDesired.Pitch = attitude[1]; - stabDesired.Yaw = attitude[2]; - stabDesired.Throttle = attitude[3]; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; - StabilizationDesiredSet(&stabDesired); -} - /** * Compute desired attitude from the desired velocity * diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index 00ef1fbe8..b93982078 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -38,6 +38,7 @@ UAVOBJSRCFILENAMES += magnetometer UAVOBJSRCFILENAMES += baroaltitude UAVOBJSRCFILENAMES += baroairspeed UAVOBJSRCFILENAMES += fixedwingpathfollowersettings +UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus UAVOBJSRCFILENAMES += flightbatterysettings UAVOBJSRCFILENAMES += firmwareiapobj UAVOBJSRCFILENAMES += flightbatterystate From 463ad550e274d34c484e3be604d448e3b370b169 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 6 Jun 2012 09:12:36 -0500 Subject: [PATCH 056/508] A few comments in my code and some simplication to the fixedwingfollower to get it compiling against my path planner. --- .../fixedwingpathfollower.c | 13 ++++--------- .../Modules/VtolPathFollower/vtolpathfollower.c | 17 ++++++++++------- .../fixedwingpathfollowersettings.xml | 3 --- 3 files changed, 14 insertions(+), 19 deletions(-) diff --git a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c index 2b26614bd..9b7904a69 100644 --- a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -244,14 +244,9 @@ static void updatePathVelocity() VelocityActualData velocityActual; VelocityActualGet(&velocityActual); - // look ahead fixedwingpathfollowerSettings.CourseFeedForward seconds - float cur[3] = {positionActual.North + (velocityActual.North * fixedwingpathfollowerSettings.CourseFeedForward), - positionActual.East + (velocityActual.East * fixedwingpathfollowerSettings.CourseFeedForward), - positionActual.Down + (velocityActual.Down * fixedwingpathfollowerSettings.CourseFeedForward) - }; struct path_status progress; - path_progress(pathDesired.Start, pathDesired.End, cur, &progress); + path_progress(pathDesired.Start, pathDesired.End, &positionActual.North, &progress); float groundspeed; float altitudeSetpoint; @@ -260,9 +255,9 @@ static void updatePathVelocity() case PATHDESIRED_MODE_ENDPOINT: default: groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * - bound(progress.fractional_progress,0,1); + bound(progress.fractional_progress,0,1); altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * - bound(progress.fractional_progress,0,1); + bound(progress.fractional_progress,0,1); break; } @@ -354,7 +349,7 @@ static uint8_t updateFixedDesiredAttitude() fixedwingpathfollowerSettings.AirSpeedMax); // Airspeed error - speedError = airspeedDesired - ( airspeedActual ); + speedError = airspeedDesired - airspeedActual; // Vertical error climbspeedDesired = bound ( velocityDesired.Down, diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 66b7630a4..4ccff790a 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -3,9 +3,9 @@ * * @file vtolpathfollower.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint - * and sets @ref AttitudeDesired. It only does this when the FlightMode field - * of @ref ManualControlCommand is Auto. + * @brief This module compared @ref PositionActual to @ref PathDesired + * and sets @ref Stabilization. It only does this when the FlightMode field + * of @ref FlightStatus is PathPlanner or RTH. * * @see The GNU Public License (GPL) Version 3 * @@ -27,12 +27,15 @@ */ /** - * Input object: ActiveWaypoint + * Input object: FlightStatus + * Input object: PathDesired * Input object: PositionActual - * Input object: ManualControlCommand - * Output object: AttitudeDesired + * Output object: StabilizationDesired * - * This module will periodically update the value of the AttitudeDesired object. + * This module will periodically update the value of the @ref StabilizationDesired object based on + * @ref PathDesired and @PositionActual when the Flight Mode selected in @FlightStatus is supported + * by this module. Otherwise another module (e.g. @ref ManualControlCommand) is expected to be + * writing to @ref StabilizationDesired. * * The module executes in its own thread in this example. * diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 667153a3c..0f1f109d9 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -10,9 +10,6 @@ - - - From 493864bdc445a4dbd967424c8c2548ba2a007b6f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 10:04:01 -0500 Subject: [PATCH 057/508] Add a fixed wing simulator mode --- flight/Modules/Sensors/simulated/sensors.c | 265 ++++++++++++++++++++- 1 file changed, 257 insertions(+), 8 deletions(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index b9e830dbb..e42ce2ce6 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -84,13 +84,15 @@ static void SensorsTask(void *parameters); static void simulateConstant(); static void simulateModelAgnostic(); static void simulateModelQuadcopter(); +static void simulateModelAirplane(); static float accel_bias[3]; static float rand_gauss(); -enum sensor_sim_type {CONSTANT, MODEL_AGNOSTIC, MODEL_QUADCOPTER} sensor_sim_type; +enum sensor_sim_type {CONSTANT, MODEL_AGNOSTIC, MODEL_QUADCOPTER, MODEL_AIRPLANE} sensor_sim_type; +#define GRAV 9.81 /** * Initialise the module. Called before the start function * \returns 0 on success or -1 if initialisation failed @@ -152,7 +154,7 @@ static void SensorsTask(void *parameters) // homeLocation.Set = HOMELOCATION_SET_TRUE; // HomeLocationSet(&homeLocation); - sensor_sim_type = MODEL_QUADCOPTER; + sensor_sim_type = MODEL_AIRPLANE; // Main task loop lastSysTime = xTaskGetTickCount(); @@ -180,6 +182,8 @@ static void SensorsTask(void *parameters) case MODEL_QUADCOPTER: simulateModelQuadcopter(); break; + case MODEL_AIRPLANE: + simulateModelAirplane(); } vTaskDelay(2 / portTICK_RATE_MS); @@ -192,7 +196,7 @@ static void simulateConstant() AccelsData accelsData; // Skip get as we set all the fields accelsData.x = 0; accelsData.y = 0; - accelsData.z = -9.81; + accelsData.z = -GRAV; accelsData.temperature = 0; AccelsSet(&accelsData); @@ -246,9 +250,9 @@ static void simulateModelAgnostic() Quaternion2R(q,Rbe); AccelsData accelsData; // Skip get as we set all the fields - accelsData.x = -9.81 * Rbe[0][2]; - accelsData.y = -9.81 * Rbe[1][2]; - accelsData.z = -9.81 * Rbe[2][2]; + accelsData.x = -GRAV * Rbe[0][2]; + accelsData.y = -GRAV * Rbe[1][2]; + accelsData.z = -GRAV * Rbe[2][2]; accelsData.temperature = 30; AccelsSet(&accelsData); @@ -303,7 +307,7 @@ static void simulateModelQuadcopter() float Rbe[3][3]; const float ACTUATOR_ALPHA = 0.8; - const float MAX_THRUST = 9.81 * 2; + const float MAX_THRUST = GRAV * 2; const float K_FRICTION = 1; const float GPS_PERIOD = 0.1; const float MAG_PERIOD = 1.0 / 75.0; @@ -391,7 +395,7 @@ static void simulateModelQuadcopter() ned_accel[0] = -thrust * Rbe[2][0]; ned_accel[1] = -thrust * Rbe[2][1]; // Gravity causes acceleration of 9.81 in the down direction - ned_accel[2] = -thrust * Rbe[2][2] + 9.81; + ned_accel[2] = -thrust * Rbe[2][2] + GRAV; // Apply acceleration based on velocity ned_accel[0] -= K_FRICTION * (vel[0] - wind[0]); @@ -517,6 +521,251 @@ static void simulateModelQuadcopter() AttitudeSimulatedSet(&attitudeSimulated); } +/** + * This method performs a simple simulation of a quadcopter + * + * It takes in the ActuatorDesired command to rotate the aircraft and performs + * a simple kinetic model where the throttle increases the energy and drag decreases + * it. Changing altitude moves energy from kinetic to potential. + * + * 1. Update attitude based on ActuatorDesired + * 2. Update position based on velocity + */ +static void simulateModelAirplane() +{ + static double pos[3] = {0,0,0}; + static double vel[3] = {0,0,0}; + static double ned_accel[3] = {0,0,0}; + static float q[4] = {1,0,0,0}; + static float rpy[3] = {0,0,0}; // Low pass filtered actuator + static float baro_offset = 0.0f; + float Rbe[3][3]; + + const float ACTUATOR_ALPHA = 0.8; + const float MAX_THRUST = 9.81 * 2; + const float K_FRICTION = 1; + const float GPS_PERIOD = 0.1; + const float MAG_PERIOD = 1.0 / 75.0; + const float BARO_PERIOD = 1.0 / 20.0; + + static uint32_t last_time; + + float dT = (PIOS_DELAY_DiffuS(last_time) / 1e6); + if(dT < 1e-3) + dT = 2e-3; + last_time = PIOS_DELAY_GetRaw(); + + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + ActuatorDesiredData actuatorDesired; + ActuatorDesiredGet(&actuatorDesired); + + float thrust = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) ? actuatorDesired.Throttle * MAX_THRUST : 0; + if (thrust < 0) + thrust = 0; + + if (thrust != thrust) + thrust = 0; + + // float control_scaling = thrust * thrustToDegs; + // // In rad/s + // rpy[0] = control_scaling * actuatorDesired.Roll * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; + // rpy[1] = control_scaling * actuatorDesired.Pitch * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; + // rpy[2] = control_scaling * actuatorDesired.Yaw * (1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; + // + // GyrosData gyrosData; // Skip get as we set all the fields + // gyrosData.x = rpy[0] * 180 / M_PI + rand_gauss(); + // gyrosData.y = rpy[1] * 180 / M_PI + rand_gauss(); + // gyrosData.z = rpy[2] * 180 / M_PI + rand_gauss(); + + /**** 1. Update attitude ****/ + RateDesiredData rateDesired; + RateDesiredGet(&rateDesired); + + rpy[0] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Roll * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; + rpy[1] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Pitch * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; + rpy[2] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Yaw * (1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; + + GyrosData gyrosData; // Skip get as we set all the fields + gyrosData.x = rpy[0] + rand_gauss(); + gyrosData.y = rpy[1] + rand_gauss(); + gyrosData.z = rpy[2] + rand_gauss(); + GyrosSet(&gyrosData); + + // Predict the attitude forward in time + float qdot[4]; + qdot[0] = (-q[1] * rpy[0] - q[2] * rpy[1] - q[3] * rpy[2]) * dT * M_PI / 180 / 2; + qdot[1] = (q[0] * rpy[0] - q[3] * rpy[1] + q[2] * rpy[2]) * dT * M_PI / 180 / 2; + qdot[2] = (q[3] * rpy[0] + q[0] * rpy[1] - q[1] * rpy[2]) * dT * M_PI / 180 / 2; + qdot[3] = (-q[2] * rpy[0] + q[1] * rpy[1] + q[0] * rpy[2]) * dT * M_PI / 180 / 2; + + // Take a time step + q[0] = q[0] + qdot[0]; + q[1] = q[1] + qdot[1]; + q[2] = q[2] + qdot[2]; + q[3] = q[3] + qdot[3]; + + float qmag = sqrtf(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); + q[0] = q[0] / qmag; + q[1] = q[1] / qmag; + q[2] = q[2] / qmag; + q[3] = q[3] / qmag; + + if(overideAttitude){ + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + attitudeActual.q1 = q[0]; + attitudeActual.q2 = q[1]; + attitudeActual.q3 = q[2]; + attitudeActual.q4 = q[3]; + AttitudeActualSet(&attitudeActual); + } + + /**** 2. Update position based on velocity ****/ + static float wind[3] = {0,0,0}; + wind[0] = wind[0] * 0.95 + rand_gauss() / 10.0; + wind[1] = wind[1] * 0.95 + rand_gauss() / 10.0; + wind[2] = wind[2] * 0.95 + rand_gauss() / 10.0; + + /* Compute aerodynamic forces in body referenced frame. Later use more sophisticated equations */ + /* TODO: This should become more accurate. Use the force equations to calculate lift from the */ + /* various surfaces based on AoA and airspeed. From that compute torques and forces. For later */ + double forces[3]; // X, Y, Z + forces[0] = thrust; // Friction is applied in all directions in NED + forces[1] = 0; // No side slip + forces[2] = GRAV; // Stupidly simple, always have gravity lift when straight and level + + Quaternion2R(q,Rbe); + // Negate force[2] as NED defines down as possitive, aircraft convention is Z up is positive (?) + ned_accel[0] = forces[0] * Rbe[0][0] + forces[1] * Rbe[1][0] - forces[2] * Rbe[2][0]; + ned_accel[1] = forces[0] * Rbe[0][1] + forces[1] * Rbe[1][1] - forces[2] * Rbe[2][1]; + ned_accel[2] = forces[0] * Rbe[0][2] + forces[1] * Rbe[1][2] - forces[2] * Rbe[2][2]; + // Gravity causes acceleration of 9.81 in the down direction + ned_accel[2] += 9.81; + + // Apply acceleration based on velocity + ned_accel[0] -= K_FRICTION * (vel[0] - wind[0]); + ned_accel[1] -= K_FRICTION * (vel[1] - wind[0]); + ned_accel[2] -= K_FRICTION * (vel[2] - wind[0]); + + // Predict the velocity forward in time + vel[0] = vel[0] + ned_accel[0] * dT; + vel[1] = vel[1] + ned_accel[1] * dT; + vel[2] = vel[2] + ned_accel[2] * dT; + + // Predict the position forward in time + pos[0] = pos[0] + vel[0] * dT; + pos[1] = pos[1] + vel[1] * dT; + pos[2] = pos[2] + vel[2] * dT; + + // Simulate hitting ground + if(pos[2] > 0) { + pos[2] = 0; + vel[2] = 0; + ned_accel[2] = 0; + } + + // Sensor feels gravity (when not acceleration in ned frame e.g. ned_accel[2] = 0) + ned_accel[2] -= GRAV; + + // Transform the accels back in to body frame + AccelsData accelsData; // Skip get as we set all the fields + accelsData.x = ned_accel[0] * Rbe[0][0] + ned_accel[1] * Rbe[0][1] + ned_accel[2] * Rbe[0][2] + accel_bias[0]; + accelsData.y = ned_accel[0] * Rbe[1][0] + ned_accel[1] * Rbe[1][1] + ned_accel[2] * Rbe[1][2] + accel_bias[1]; + accelsData.z = ned_accel[0] * Rbe[2][0] + ned_accel[1] * Rbe[2][1] + ned_accel[2] * Rbe[2][2] + accel_bias[2]; + accelsData.temperature = 30; + AccelsSet(&accelsData); + + if(baro_offset == 0) { + // Hacky initialization + baro_offset = 50;// * rand_gauss(); + } else { + // Very small drift process + baro_offset += rand_gauss() / 100; + } + // Update baro periodically + static uint32_t last_baro_time = 0; + if(PIOS_DELAY_DiffuS(last_baro_time) / 1.0e6 > BARO_PERIOD) { + BaroAltitudeData baroAltitude; + BaroAltitudeGet(&baroAltitude); + baroAltitude.Altitude = -pos[2] + baro_offset; + BaroAltitudeSet(&baroAltitude); + last_baro_time = PIOS_DELAY_GetRaw(); + } + + HomeLocationData homeLocation; + HomeLocationGet(&homeLocation); + + static float gps_vel_drift[3] = {0,0,0}; + gps_vel_drift[0] = gps_vel_drift[0] * 0.65 + rand_gauss() / 5.0; + gps_vel_drift[1] = gps_vel_drift[1] * 0.65 + rand_gauss() / 5.0; + gps_vel_drift[2] = gps_vel_drift[2] * 0.65 + rand_gauss() / 5.0; + + // Update GPS periodically + static uint32_t last_gps_time = 0; + if(PIOS_DELAY_DiffuS(last_gps_time) / 1.0e6 > GPS_PERIOD) { + // Use double precision here as simulating what GPS produces + double T[3]; + T[0] = homeLocation.Altitude+6.378137E6f * M_PI / 180.0; + T[1] = cos(homeLocation.Latitude / 10e6 * M_PI / 180.0f)*(homeLocation.Altitude+6.378137E6) * M_PI / 180.0; + T[2] = -1.0; + + static float gps_drift[3] = {0,0,0}; + gps_drift[0] = gps_drift[0] * 0.95 + rand_gauss() / 10.0; + gps_drift[1] = gps_drift[1] * 0.95 + rand_gauss() / 10.0; + gps_drift[2] = gps_drift[2] * 0.95 + rand_gauss() / 10.0; + + GPSPositionData gpsPosition; + GPSPositionGet(&gpsPosition); + gpsPosition.Latitude = homeLocation.Latitude + ((pos[0] + gps_drift[0]) / T[0] * 10.0e6); + gpsPosition.Longitude = homeLocation.Longitude + ((pos[1] + gps_drift[1])/ T[1] * 10.0e6); + gpsPosition.Altitude = homeLocation.Altitude + ((pos[2] + gps_drift[2]) / T[2]); + gpsPosition.Groundspeed = sqrt(pow(vel[0] + gps_vel_drift[0],2) + pow(vel[1] + gps_vel_drift[1],2)); + gpsPosition.Heading = 180 / M_PI * atan2(vel[1] + gps_vel_drift[1],vel[0] + gps_vel_drift[0]); + gpsPosition.Satellites = 7; + gpsPosition.PDOP = 1; + GPSPositionSet(&gpsPosition); + last_gps_time = PIOS_DELAY_GetRaw(); + } + + // Update GPS Velocity measurements + static uint32_t last_gps_vel_time = 1000; // Delay by a millisecond + if(PIOS_DELAY_DiffuS(last_gps_vel_time) / 1.0e6 > GPS_PERIOD) { + GPSVelocityData gpsVelocity; + GPSVelocityGet(&gpsVelocity); + gpsVelocity.North = vel[0] + gps_vel_drift[0]; + gpsVelocity.East = vel[1] + gps_vel_drift[1]; + gpsVelocity.Down = vel[2] + gps_vel_drift[2]; + GPSVelocitySet(&gpsVelocity); + last_gps_vel_time = PIOS_DELAY_GetRaw(); + } + + // Update mag periodically + static uint32_t last_mag_time = 0; + if(PIOS_DELAY_DiffuS(last_mag_time) / 1.0e6 > MAG_PERIOD) { + MagnetometerData mag; + mag.x = homeLocation.Be[0] * Rbe[0][0] + homeLocation.Be[1] * Rbe[0][1] + homeLocation.Be[2] * Rbe[0][2]; + mag.y = homeLocation.Be[0] * Rbe[1][0] + homeLocation.Be[1] * Rbe[1][1] + homeLocation.Be[2] * Rbe[1][2]; + mag.z = homeLocation.Be[0] * Rbe[2][0] + homeLocation.Be[1] * Rbe[2][1] + homeLocation.Be[2] * Rbe[2][2]; + MagnetometerSet(&mag); + last_mag_time = PIOS_DELAY_GetRaw(); + } + + AttitudeSimulatedData attitudeSimulated; + AttitudeSimulatedGet(&attitudeSimulated); + attitudeSimulated.q1 = q[0]; + attitudeSimulated.q2 = q[1]; + attitudeSimulated.q3 = q[2]; + attitudeSimulated.q4 = q[3]; + Quaternion2RPY(q,&attitudeSimulated.Roll); + attitudeSimulated.Position[0] = pos[0]; + attitudeSimulated.Position[1] = pos[1]; + attitudeSimulated.Position[2] = pos[2]; + attitudeSimulated.Velocity[0] = vel[0]; + attitudeSimulated.Velocity[1] = vel[1]; + attitudeSimulated.Velocity[2] = vel[2]; + AttitudeSimulatedSet(&attitudeSimulated); +} static float rand_gauss (void) { float v1,v2,s; From 823538dbbb03738226977e78e2818a67f47b6247 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 10:13:38 -0500 Subject: [PATCH 058/508] Forgot the fixed wing follower status --- ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index f639f0631..4a7451c9f 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -41,6 +41,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.h \ + $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.h \ $$UAVOBJECT_SYNTHETICS/systemstats.h \ $$UAVOBJECT_SYNTHETICS/systemalarms.h \ $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ @@ -122,6 +123,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/actuatordesired.cpp \ $$UAVOBJECT_SYNTHETICS/actuatorcommand.cpp \ $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.cpp \ + $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.cpp \ $$UAVOBJECT_SYNTHETICS/gpsposition.cpp \ $$UAVOBJECT_SYNTHETICS/gpstime.cpp \ $$UAVOBJECT_SYNTHETICS/gpssatellites.cpp \ From 6605d861dddef2afba2f1f73f59d45bdf727f8e9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 11:08:11 -0500 Subject: [PATCH 059/508] Add cross coupling between roll and heading to make simulator fly like a plane :D --- flight/Modules/Sensors/simulated/sensors.c | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index e42ce2ce6..82cb4a1c8 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -547,6 +547,7 @@ static void simulateModelAirplane() const float GPS_PERIOD = 0.1; const float MAG_PERIOD = 1.0 / 75.0; const float BARO_PERIOD = 1.0 / 20.0; + const float ROLL_HEADING_COUPLING = 0.1; // (deg/s) heading change per deg of roll static uint32_t last_time; @@ -582,10 +583,19 @@ static void simulateModelAirplane() RateDesiredData rateDesired; RateDesiredGet(&rateDesired); + // Need to compute roll angle for easy cross coupling + //Quaternion2RPY(q,rpy); + //float roll = rpy[0]; + rpy[0] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Roll * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; rpy[1] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Pitch * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; rpy[2] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Yaw * (1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; - + { + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + rpy[2] += attitudeActual.Roll * ROLL_HEADING_COUPLING; + } + GyrosData gyrosData; // Skip get as we set all the fields gyrosData.x = rpy[0] + rand_gauss(); gyrosData.y = rpy[1] + rand_gauss(); From bcaeda98f799c73a14e5596a2c714d1ace410e89 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 11:14:15 -0500 Subject: [PATCH 060/508] Fix bug in wind speed usage for simulation --- flight/Modules/Sensors/simulated/sensors.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index 82cb4a1c8..d5c4682db 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -399,8 +399,8 @@ static void simulateModelQuadcopter() // Apply acceleration based on velocity ned_accel[0] -= K_FRICTION * (vel[0] - wind[0]); - ned_accel[1] -= K_FRICTION * (vel[1] - wind[0]); - ned_accel[2] -= K_FRICTION * (vel[2] - wind[0]); + ned_accel[1] -= K_FRICTION * (vel[1] - wind[1]); + ned_accel[2] -= K_FRICTION * (vel[2] - wind[2]); // Predict the velocity forward in time vel[0] = vel[0] + ned_accel[0] * dT; @@ -655,8 +655,8 @@ static void simulateModelAirplane() // Apply acceleration based on velocity ned_accel[0] -= K_FRICTION * (vel[0] - wind[0]); - ned_accel[1] -= K_FRICTION * (vel[1] - wind[0]); - ned_accel[2] -= K_FRICTION * (vel[2] - wind[0]); + ned_accel[1] -= K_FRICTION * (vel[1] - wind[1]); + ned_accel[2] -= K_FRICTION * (vel[2] - wind[2]); // Predict the velocity forward in time vel[0] = vel[0] + ned_accel[0] * dT; From 53c9b4c8a48c80f1e6e2741645cca6ea68f7000c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 11:23:35 -0500 Subject: [PATCH 061/508] Add simulated baro airspeed. PathFollower functionality tested and works. --- flight/Modules/Sensors/simulated/sensors.c | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index d5c4682db..07310531b 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -54,6 +54,7 @@ #include "attitudeactual.h" #include "attitudesimulated.h" #include "attitudesettings.h" +#include "baroairspeed.h" #include "baroaltitude.h" #include "gyros.h" #include "gyrosbias.h" @@ -107,6 +108,7 @@ int32_t SensorsInitialize(void) AccelsInitialize(); AttitudeSimulatedInitialize(); BaroAltitudeInitialize(); + BaroAirspeedInitialize(); GyrosInitialize(); GyrosBiasInitialize(); GPSPositionInitialize(); @@ -703,6 +705,22 @@ static void simulateModelAirplane() last_baro_time = PIOS_DELAY_GetRaw(); } + // Update baro airpseed periodically + static uint32_t last_airspeed_time = 0; + if(PIOS_DELAY_DiffuS(last_airspeed_time) / 1.0e6 > BARO_PERIOD) { + // Rbe takes a vector from body to earth. If we take (1,0,0)^T through this and then dot with airspeed + // we get forward airspeed + float airspeed[3] = {vel[0] - wind[0], vel[1] - wind[1], vel[2] - wind[2]}; + float forwardSpeed = Rbe[0][0] * airspeed[0] + Rbe[1][0] * airspeed[1] + Rbe[2][0] * airspeed[2]; + + BaroAirspeedData baroAirspeed; + baroAirspeed.Connected = BAROAIRSPEED_CONNECTED_TRUE; + baroAirspeed.ZeroPoint = 0; + baroAirspeed.Airspeed = forwardSpeed; + BaroAirspeedSet(&baroAirspeed); + last_airspeed_time = PIOS_DELAY_GetRaw(); + } + HomeLocationData homeLocation; HomeLocationGet(&homeLocation); From 980111d246ed149212e6520a4e312ec931cd121b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 11:44:00 -0500 Subject: [PATCH 062/508] Make RTH mode default to 2 m/s. This needs to be in a UAVO somewhere (ManualControlSettings?) --- flight/Modules/ManualControl/manualcontrol.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index bbe0c3465..f19a1847d 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -649,6 +649,8 @@ static void setRTH(bool changed) pathDesired.End[PATHDESIRED_END_NORTH] = 0; pathDesired.End[PATHDESIRED_END_EAST] = 0; pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down - 10; + pathDesired.StartingVelocity = 2; + pathDesired.EndingVelocity = 2; pathDesired.Mode = PATHDESIRED_MODE_ENDPOINT; PathDesiredSet(&pathDesired); } From ccee8e09f43cf7f427ee5cb96cfbead37835db94 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 11:44:22 -0500 Subject: [PATCH 063/508] Cheat. For FW navigation when doing endpoint mode plot path from current position to endpoint. --- .../FixedWingPathFollower/fixedwingpathfollower.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c index 9b7904a69..8b700d128 100644 --- a/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c +++ b/flight/Modules/FixedWingPathFollower/fixedwingpathfollower.c @@ -245,20 +245,26 @@ static void updatePathVelocity() VelocityActualGet(&velocityActual); struct path_status progress; - - path_progress(pathDesired.Start, pathDesired.End, &positionActual.North, &progress); float groundspeed; float altitudeSetpoint; switch (pathDesired.Mode) { case PATHDESIRED_MODE_PATH: - case PATHDESIRED_MODE_ENDPOINT: - default: + path_progress(pathDesired.Start, pathDesired.End, &positionActual.North, &progress); groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * bound(progress.fractional_progress,0,1); altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * bound(progress.fractional_progress,0,1); break; + case PATHDESIRED_MODE_ENDPOINT: + path_progress(&positionActual.North, pathDesired.End, &positionActual.North, &progress); + groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * + bound(progress.fractional_progress,0,1); + altitudeSetpoint = pathDesired.Start[2] + (pathDesired.End[2] - pathDesired.Start[2]) * + bound(progress.fractional_progress,0,1); + break; + default: + break; } // calculate velocity - can be zero if waypoints are too close From 3af9ea9174591806276c76c045926eaac87b7f9a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 13:01:50 -0500 Subject: [PATCH 064/508] In OSG load an airframe model that matches the system settings. This needs to come from a resource file though. --- .../plugins/osgearthview/osgviewerwidget.cpp | 24 ++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/osgearthview/osgviewerwidget.cpp b/ground/openpilotgcs/src/plugins/osgearthview/osgviewerwidget.cpp index e8a2b5436..b15862b50 100644 --- a/ground/openpilotgcs/src/plugins/osgearthview/osgviewerwidget.cpp +++ b/ground/openpilotgcs/src/plugins/osgearthview/osgviewerwidget.cpp @@ -99,6 +99,7 @@ using namespace osgEarth::Annotation; #include "gpsposition.h" #include "homelocation.h" #include "positionactual.h" +#include "systemsettings.h" using namespace Utils; @@ -208,7 +209,28 @@ osg::Camera* OsgViewerWidget::createCamera( int x, int y, int w, int h, const st osg::Node* OsgViewerWidget::createAirplane() { osg::Group* model = new osg::Group; - osg::Node *uav = osgDB::readNodeFile("/Users/jcotton81/Documents/Programming/OpenPilot/artwork/3D Model/multi/joes_cnc/J14-QT_+.3DS"); + osg::Node *uav; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UAVObjectManager * objMngr = pm->getObject(); + Q_ASSERT(objMngr); + + SystemSettings *systemSettingsObj = SystemSettings::GetInstance(objMngr); + SystemSettings::DataFields systemSettings = systemSettingsObj->getData(); + + qDebug() << "Frame type:" << systemSettingsObj->getField("AirframeType")->getValue().toString(); + // Get model that matches airframe type + switch(systemSettings.AirframeType) { + case SystemSettings::AIRFRAMETYPE_FIXEDWING: + case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: + case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: + uav = osgDB::readNodeFile("/Users/jcotton81/Documents/Programming/OpenPilot/artwork/3D Model/planes/Easystar/easystar.3ds"); + break; + default: + uav = osgDB::readNodeFile("/Users/jcotton81/Documents/Programming/OpenPilot/artwork/3D Model/multi/joes_cnc/J14-QT_+.3DS"); + } + if(uav) { uavAttitudeAndScale = new osg::MatrixTransform(); uavAttitudeAndScale->setMatrix(osg::Matrixd::scale(0.2e0,0.2e0,0.2e0)); From ac9adb0c946725624ba86876a4caa0872493cbfe Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 13:54:17 -0500 Subject: [PATCH 065/508] Improve the airplane modeling a bit to the point navigation now keeps altitude and speed correctly --- flight/Modules/Sensors/simulated/sensors.c | 46 ++++++++++++---------- 1 file changed, 26 insertions(+), 20 deletions(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index 07310531b..cd8aa42ff 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -545,11 +545,12 @@ static void simulateModelAirplane() const float ACTUATOR_ALPHA = 0.8; const float MAX_THRUST = 9.81 * 2; - const float K_FRICTION = 1; + const float K_FRICTION = 0.2; const float GPS_PERIOD = 0.1; const float MAG_PERIOD = 1.0 / 75.0; const float BARO_PERIOD = 1.0 / 20.0; const float ROLL_HEADING_COUPLING = 0.1; // (deg/s) heading change per deg of roll + const float PITCH_THRUST_COUPLING = 0.2; // (m/s^2) of forward acceleration per deg of pitch static uint32_t last_time; @@ -585,18 +586,17 @@ static void simulateModelAirplane() RateDesiredData rateDesired; RateDesiredGet(&rateDesired); - // Need to compute roll angle for easy cross coupling - //Quaternion2RPY(q,rpy); - //float roll = rpy[0]; - + // Need to get roll angle for easy cross coupling + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + double roll = attitudeActual.Roll; + double pitch = attitudeActual.Pitch; + rpy[0] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Roll * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; rpy[1] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Pitch * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; rpy[2] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Yaw * (1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; - { - AttitudeActualData attitudeActual; - AttitudeActualGet(&attitudeActual); - rpy[2] += attitudeActual.Roll * ROLL_HEADING_COUPLING; - } + rpy[2] += roll * ROLL_HEADING_COUPLING; + GyrosData gyrosData; // Skip get as we set all the fields gyrosData.x = rpy[0] + rand_gauss(); @@ -638,16 +638,27 @@ static void simulateModelAirplane() wind[0] = wind[0] * 0.95 + rand_gauss() / 10.0; wind[1] = wind[1] * 0.95 + rand_gauss() / 10.0; wind[2] = wind[2] * 0.95 + rand_gauss() / 10.0; + wind[0] = 0; + wind[1] = 0; + wind[2] = 0; + + // Rbe takes a vector from body to earth. If we take (1,0,0)^T through this and then dot with airspeed + // we get forward airspeed + Quaternion2R(q,Rbe); + + double airspeed[3] = {vel[0] - wind[0], vel[1] - wind[1], vel[2] - wind[2]}; + double forwardAirspeed = Rbe[0][0] * airspeed[0] + Rbe[0][1] * airspeed[1] + Rbe[0][2] * airspeed[2]; + double sidewaysAirspeed = Rbe[1][0] * airspeed[0] + Rbe[1][1] * airspeed[1] + Rbe[1][2] * airspeed[2]; + double downwardAirspeed = Rbe[2][0] * airspeed[0] + Rbe[2][1] * airspeed[1] + Rbe[2][2] * airspeed[2]; /* Compute aerodynamic forces in body referenced frame. Later use more sophisticated equations */ /* TODO: This should become more accurate. Use the force equations to calculate lift from the */ /* various surfaces based on AoA and airspeed. From that compute torques and forces. For later */ double forces[3]; // X, Y, Z - forces[0] = thrust; // Friction is applied in all directions in NED - forces[1] = 0; // No side slip - forces[2] = GRAV; // Stupidly simple, always have gravity lift when straight and level + forces[0] = thrust - pitch * PITCH_THRUST_COUPLING - forwardAirspeed * K_FRICTION; // Friction is applied in all directions in NED + forces[1] = 0 - sidewaysAirspeed * K_FRICTION * 100; // No side slip + forces[2] = GRAV + downwardAirspeed * K_FRICTION * 100; // Stupidly simple, always have gravity lift when straight and level - Quaternion2R(q,Rbe); // Negate force[2] as NED defines down as possitive, aircraft convention is Z up is positive (?) ned_accel[0] = forces[0] * Rbe[0][0] + forces[1] * Rbe[1][0] - forces[2] * Rbe[2][0]; ned_accel[1] = forces[0] * Rbe[0][1] + forces[1] * Rbe[1][1] - forces[2] * Rbe[2][1]; @@ -708,15 +719,10 @@ static void simulateModelAirplane() // Update baro airpseed periodically static uint32_t last_airspeed_time = 0; if(PIOS_DELAY_DiffuS(last_airspeed_time) / 1.0e6 > BARO_PERIOD) { - // Rbe takes a vector from body to earth. If we take (1,0,0)^T through this and then dot with airspeed - // we get forward airspeed - float airspeed[3] = {vel[0] - wind[0], vel[1] - wind[1], vel[2] - wind[2]}; - float forwardSpeed = Rbe[0][0] * airspeed[0] + Rbe[1][0] * airspeed[1] + Rbe[2][0] * airspeed[2]; - BaroAirspeedData baroAirspeed; baroAirspeed.Connected = BAROAIRSPEED_CONNECTED_TRUE; baroAirspeed.ZeroPoint = 0; - baroAirspeed.Airspeed = forwardSpeed; + baroAirspeed.Airspeed = forwardAirspeed; BaroAirspeedSet(&baroAirspeed); last_airspeed_time = PIOS_DELAY_GetRaw(); } From 6ca34d3d0cce0557bd36cb09e03b79ef2469bb89 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 13:58:18 -0500 Subject: [PATCH 066/508] Make lift model dependent on airspeed. --- flight/Modules/Sensors/simulated/sensors.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index cd8aa42ff..933e95279 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -543,6 +543,7 @@ static void simulateModelAirplane() static float baro_offset = 0.0f; float Rbe[3][3]; + const float LIFT_SPEED = 8; // (m/s) where achieve lift for zero pitch const float ACTUATOR_ALPHA = 0.8; const float MAX_THRUST = 9.81 * 2; const float K_FRICTION = 0.2; @@ -657,7 +658,7 @@ static void simulateModelAirplane() double forces[3]; // X, Y, Z forces[0] = thrust - pitch * PITCH_THRUST_COUPLING - forwardAirspeed * K_FRICTION; // Friction is applied in all directions in NED forces[1] = 0 - sidewaysAirspeed * K_FRICTION * 100; // No side slip - forces[2] = GRAV + downwardAirspeed * K_FRICTION * 100; // Stupidly simple, always have gravity lift when straight and level + forces[2] = GRAV * (forwardAirspeed - LIFT_SPEED) + downwardAirspeed * K_FRICTION * 100; // Stupidly simple, always have gravity lift when straight and level // Negate force[2] as NED defines down as possitive, aircraft convention is Z up is positive (?) ned_accel[0] = forces[0] * Rbe[0][0] + forces[1] * Rbe[1][0] - forces[2] * Rbe[2][0]; From ac99176f73805010e30e623efc4ba5b553d9d780 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 8 Jun 2012 14:12:52 -0500 Subject: [PATCH 067/508] Add a scale to the logo --- flight/Modules/PathPlanner/pathplanner.c | 38 +++++++++++++----------- 1 file changed, 20 insertions(+), 18 deletions(-) diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index 4dc4db5c0..1a5ba6f8d 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -341,12 +341,14 @@ static void createPathBox() static void createPathLogo() { + float scale = 1; + // Draw O WaypointData waypoint; waypoint.Velocity[0] = 2; // Since for now this isn't directional just set a mag for(uint32_t i = 0; i < 20; i++) { - waypoint.Position[1] = 30 * cos(i / 19.0 * 2 * M_PI); - waypoint.Position[0] = 50 * sin(i / 19.0 * 2 * M_PI); + waypoint.Position[1] = scale * 30 * cos(i / 19.0 * 2 * M_PI); + waypoint.Position[0] = scale * 50 * sin(i / 19.0 * 2 * M_PI); waypoint.Position[2] = -50; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); @@ -355,59 +357,59 @@ static void createPathLogo() // Draw P for(uint32_t i = 20; i < 35; i++) { - waypoint.Position[1] = 55 + 20 * cos(i / 10.0 * M_PI - M_PI / 2); - waypoint.Position[0] = 25 + 25 * sin(i / 10.0 * M_PI - M_PI / 2); + waypoint.Position[1] = scale * (55 + 20 * cos(i / 10.0 * M_PI - M_PI / 2)); + waypoint.Position[0] = scale * (25 + 25 * sin(i / 10.0 * M_PI - M_PI / 2)); waypoint.Position[2] = -50; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); bad_inits += (WaypointInstSet(i, &waypoint) != 0); } - waypoint.Position[1] = 35; - waypoint.Position[0] = -50; + waypoint.Position[1] = scale * 35; + waypoint.Position[0] = scale * -50; waypoint.Position[2] = -50; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(35, &waypoint); // Draw Box - waypoint.Position[1] = 35; - waypoint.Position[0] = -60; + waypoint.Position[1] = scale * 35; + waypoint.Position[0] = scale * -60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(36, &waypoint); - waypoint.Position[1] = 85; - waypoint.Position[0] = -60; + waypoint.Position[1] = scale * 85; + waypoint.Position[0] = scale * -60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(37, &waypoint); - waypoint.Position[1] = 85; - waypoint.Position[0] = 60; + waypoint.Position[1] = scale * 85; + waypoint.Position[0] = scale * 60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(38, &waypoint); - waypoint.Position[1] = -40; - waypoint.Position[0] = 60; + waypoint.Position[1] = scale * -40; + waypoint.Position[0] = scale * 60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(39, &waypoint); - waypoint.Position[1] = -40; - waypoint.Position[0] = -60; + waypoint.Position[1] = scale * -40; + waypoint.Position[0] = scale * -60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); WaypointInstSet(40, &waypoint); - waypoint.Position[1] = 35; - waypoint.Position[0] = -60; + waypoint.Position[1] = scale * 35; + waypoint.Position[0] = scale * -60; waypoint.Position[2] = -30; waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; WaypointCreateInstance(); From d2a3e39bbf083a8ac72533074d17c64877a5ac7c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 9 Jun 2012 11:06:41 -0500 Subject: [PATCH 068/508] Get mag before gyros so that when gyro chip is acting up we still see mag data. Helpful for board diagnostics. --- flight/Modules/Sensors/sensors.c | 51 +++++++++++++++----------------- 1 file changed, 24 insertions(+), 27 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index c854aa37a..900a3ee54 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -241,6 +241,30 @@ static void SensorsTask(void *parameters) accel_samples = 0; gyro_samples = 0; +#if defined(PIOS_INCLUDE_HMC5883) + MagnetometerData mag; + if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) { + int16_t values[3]; + PIOS_HMC5883_ReadMag(values); + float mags[3] = {(float) values[1] * mag_scale[0] - mag_bias[0], + (float) values[0] * mag_scale[1] - mag_bias[1], + -(float) values[2] * mag_scale[2] - mag_bias[2]}; + if (rotate) { + float mag_out[3]; + rot_mult(R, mags, mag_out); + mag.x = mag_out[0]; + mag.y = mag_out[1]; + mag.z = mag_out[2]; + } else { + mag.x = mags[0]; + mag.y = mags[1]; + mag.z = mags[2]; + } + MagnetometerSet(&mag); + mag_update_time = PIOS_DELAY_GetRaw(); + } +#endif + AccelsData accelsData; GyrosData gyrosData; @@ -384,33 +408,6 @@ static void SensorsTask(void *parameters) gyrosData.z += gyrosBias.z; } GyrosSet(&gyrosData); - - // Because most crafts wont get enough information from gravity to zero yaw gyro, we try - // and make it average zero (weakly) - -#if defined(PIOS_INCLUDE_HMC5883) - MagnetometerData mag; - if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) { - int16_t values[3]; - PIOS_HMC5883_ReadMag(values); - float mags[3] = {(float) values[1] * mag_scale[0] - mag_bias[0], - (float) values[0] * mag_scale[1] - mag_bias[1], - -(float) values[2] * mag_scale[2] - mag_bias[2]}; - if (rotate) { - float mag_out[3]; - rot_mult(R, mags, mag_out); - mag.x = mag_out[0]; - mag.y = mag_out[1]; - mag.z = mag_out[2]; - } else { - mag.x = mags[0]; - mag.y = mags[1]; - mag.z = mags[2]; - } - MagnetometerSet(&mag); - mag_update_time = PIOS_DELAY_GetRaw(); - } -#endif PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); From f5845cb037429e8f8327a1c3955d5705704d6d7f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 9 Jun 2012 11:18:14 -0500 Subject: [PATCH 069/508] Fix self test for MPU6000 so it returns negative values per our standard --- flight/PiOS/Common/pios_mpu6000.c | 2 +- flight/PiOS/inc/pios_mpu6000.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c index f1268e83f..7df306d10 100644 --- a/flight/PiOS/Common/pios_mpu6000.c +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -354,7 +354,7 @@ float PIOS_MPU6000_GetAccelScale() * \return 0 if test succeeded * \return non-zero value if test succeeded */ -uint8_t PIOS_MPU6000_Test(void) +int32_t PIOS_MPU6000_Test(void) { /* Verify that ID matches (MPU6000 ID is 0x69) */ int32_t mpu6000_id = PIOS_MPU6000_ReadID(); diff --git a/flight/PiOS/inc/pios_mpu6000.h b/flight/PiOS/inc/pios_mpu6000.h index 191b69ed5..317b8155b 100644 --- a/flight/PiOS/inc/pios_mpu6000.h +++ b/flight/PiOS/inc/pios_mpu6000.h @@ -154,7 +154,7 @@ extern int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const stru extern xQueueHandle PIOS_MPU6000_GetQueue(); extern int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * buffer); extern int32_t PIOS_MPU6000_ReadID(); -extern uint8_t PIOS_MPU6000_Test(); +extern int32_t PIOS_MPU6000_Test(); extern float PIOS_MPU6000_GetScale(); extern float PIOS_MPU6000_GetAccelScale(); extern void PIOS_MPU6000_IRQHandler(void); From 207cc93af08927f5f25c47ae3024b44734e9e426 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 9 Jun 2012 11:39:27 -0500 Subject: [PATCH 070/508] Update the system health diagram to include warnings from the sensors module and no longer show ahrs --- .../diagrams/default/system-health.svg | 7136 +++++++++-------- 1 file changed, 3774 insertions(+), 3362 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 7667ecbb9..9fb05a1ab 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -1,5 +1,5 @@ - + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Boot Fault + +Sensors + + + From 9e5b1658b1c017250303456adf55b8c661edea2b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 9 Jun 2012 12:14:11 -0500 Subject: [PATCH 071/508] Remove AHRSComms from SystemAlarms --- shared/uavobjectdefinition/systemalarms.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index cc20045b6..91a3212ad 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -2,7 +2,7 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + elementnames="OutOfMemory,StackOverflow,CPUOverload,EventSystem,SDCard,Telemetry,ManualControl,Actuator,Attitude,Sensors,Stabilization,Guidance,Battery,FlightTime,I2C,GPS,BootFault" defaultvalue="Uninitialised"/> From 2db95a6b4f4681c53987338578029dfb4c476595 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 9 Jun 2012 12:19:08 -0500 Subject: [PATCH 072/508] Move the Sensors label position to teh correct spot --- .../share/openpilotgcs/diagrams/default/system-health.svg | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 9fb05a1ab..1d19aaf5b 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -903,8 +903,8 @@ Date: Mon, 11 Jun 2012 09:22:04 -0500 Subject: [PATCH 073/508] For now make the F4 PIOS_ADC return an error code if there is no new data in the ADC buffer. This should be handled appropriately by the caller. --- flight/PiOS/STM32F4xx/pios_adc.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/PiOS/STM32F4xx/pios_adc.c b/flight/PiOS/STM32F4xx/pios_adc.c index c88ccd5c4..53c52533e 100644 --- a/flight/PiOS/STM32F4xx/pios_adc.c +++ b/flight/PiOS/STM32F4xx/pios_adc.c @@ -292,6 +292,7 @@ void PIOS_ADC_Config(uint32_t oversampling) * @param[in] pin number * @return ADC pin value averaged over the set of samples since the last reading. * @return -1 if pin doesn't exist + * @return -2 if no data acquired since last read */ int32_t last_conv_value; int32_t PIOS_ADC_PinGet(uint32_t pin) @@ -304,6 +305,9 @@ int32_t PIOS_ADC_PinGet(uint32_t pin) return -1; } + if (accumulator[pin].accumulator <= 0) + return -2; + /* return accumulated result and clear accumulator */ result = accumulator[pin].accumulator / (accumulator[pin].count ?: 1); accumulator[pin].accumulator = 0; From 6d06daa7cdd74542d7417e26e4de7cfb26fc4b48 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 11 Jun 2012 11:21:08 -0500 Subject: [PATCH 074/508] Fix misnamed slot in the output widget --- ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index ca9a6dcc4..506c7bdec 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -79,7 +79,7 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); // Add custom handling of displaying things - connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshOutputWidgetsValues())); + connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshWidgetsValues())); addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); From ec64a50ef9e763b608e73e29874c03c2027aed3c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 11 Jun 2012 11:27:08 -0500 Subject: [PATCH 075/508] Fix the slot name in map gadget --- ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index db3704571..52ab71ae9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1616,7 +1616,7 @@ void OPMapGadgetWidget::createActions() connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); uavTrailTypeActGroup = new QActionGroup(this); - connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *))); + connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVtrailTypeActGroup_triggered(QAction*))); uavTrailTypeAct.clear(); QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); for (int i = 0; i < uav_trail_type_list.count(); i++) From c5a881086ac4a626fd86d46a8d37d5170657bf40 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 11 Jun 2012 11:30:16 -0500 Subject: [PATCH 076/508] Fix some slots in config revo calibration --- ground/openpilotgcs/src/plugins/config/configrevowidget.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index f13fc863f..45d400852 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -206,14 +206,13 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : mag_z->setTransform(QTransform::fromScale(1,0),true); // Connect the signals - connect(m_ui->ahrsCalibStart, SIGNAL(clicked()), this, SLOT(measureNoise())); connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); - connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRam())); + connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); connect(m_ui->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); From 01d47d6373b4d9abf848a993a050fd4cb8b99a5d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 11 Jun 2012 12:21:46 -0500 Subject: [PATCH 077/508] Accidental semicolon led to MPU6000 always failing self test. Another bug masked that behavior. I suck. --- flight/PiOS/Common/pios_mpu6000.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c index 7df306d10..904e9402c 100644 --- a/flight/PiOS/Common/pios_mpu6000.c +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -361,7 +361,7 @@ int32_t PIOS_MPU6000_Test(void) if(mpu6000_id < 0) return -1; - if(mpu6000_id != 0x68); + if(mpu6000_id != 0x68) return -2; return 0; From 8b9c7277a6a62d326f85dd2fb0a42ab00f311f4a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 11 Jun 2012 13:22:37 -0500 Subject: [PATCH 078/508] Remove the connection to refreshWidgetValues() in output widget. Mike was right and it's not needed since hte configTaskWidget takes care of this connection. --- .../openpilotgcs/src/plugins/config/configoutputwidget.cpp | 7 ------- .../openpilotgcs/src/plugins/config/configoutputwidget.h | 2 -- 2 files changed, 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 506c7bdec..9b3e6e01b 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -71,16 +71,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); - - firstUpdate = true; - // Configure the task widget // Connect the help button connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - // Add custom handling of displaying things - connect(this,SIGNAL(refreshWidgetsValuesRequested()), this, SLOT(refreshWidgetsValues())); - addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); // Track the ActuatorSettings object @@ -125,7 +119,6 @@ ConfigOutputWidget::~ConfigOutputWidget() */ void ConfigOutputWidget::runChannelTests(bool state) { - qDebug()<<"configoutputwidget runChannelTests"<getData(); diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index 5ccf58206..9a347d3f9 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -63,8 +63,6 @@ private: UAVObject::Metadata accInitialData; - bool firstUpdate; - bool wasItMe; private slots: void stopTests(); From bfdda0e64588e4ae378b5b0f310c892c32f7166a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 12 Jun 2012 01:51:57 -0500 Subject: [PATCH 079/508] Fix the stabilization expert UI so the label is in the right place --- .../src/plugins/config/stabilization.ui | 36 ++++++++++++++++--- 1 file changed, 31 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index fd6b01ca8..3f985a66e 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -495,7 +495,7 @@ 0 - -114 + 0 673 790 @@ -11797,7 +11797,7 @@ border-radius: 4; - + @@ -11850,7 +11850,7 @@ border-radius: 4; - + @@ -14693,6 +14693,19 @@ value as the Kp. + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -15272,7 +15285,7 @@ value as the Kp. false - + @@ -17936,7 +17949,7 @@ border-radius: 5; - + @@ -17999,6 +18012,19 @@ border-radius: 4; + + + + Qt::Horizontal + + + + 40 + 20 + + + + From 9c1fa2dfc657577f16340b72ebe4654fb8bda211 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 12 Jun 2012 13:10:24 -0500 Subject: [PATCH 080/508] Revert "Get mag before gyros so that when gyro chip is acting up we still see mag data." This reverts commit d2a3e39bbf083a8ac72533074d17c64877a5ac7c. --- flight/Modules/Sensors/sensors.c | 51 +++++++++++++++++--------------- 1 file changed, 27 insertions(+), 24 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 900a3ee54..c854aa37a 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -241,30 +241,6 @@ static void SensorsTask(void *parameters) accel_samples = 0; gyro_samples = 0; -#if defined(PIOS_INCLUDE_HMC5883) - MagnetometerData mag; - if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) { - int16_t values[3]; - PIOS_HMC5883_ReadMag(values); - float mags[3] = {(float) values[1] * mag_scale[0] - mag_bias[0], - (float) values[0] * mag_scale[1] - mag_bias[1], - -(float) values[2] * mag_scale[2] - mag_bias[2]}; - if (rotate) { - float mag_out[3]; - rot_mult(R, mags, mag_out); - mag.x = mag_out[0]; - mag.y = mag_out[1]; - mag.z = mag_out[2]; - } else { - mag.x = mags[0]; - mag.y = mags[1]; - mag.z = mags[2]; - } - MagnetometerSet(&mag); - mag_update_time = PIOS_DELAY_GetRaw(); - } -#endif - AccelsData accelsData; GyrosData gyrosData; @@ -408,6 +384,33 @@ static void SensorsTask(void *parameters) gyrosData.z += gyrosBias.z; } GyrosSet(&gyrosData); + + // Because most crafts wont get enough information from gravity to zero yaw gyro, we try + // and make it average zero (weakly) + +#if defined(PIOS_INCLUDE_HMC5883) + MagnetometerData mag; + if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 150000) { + int16_t values[3]; + PIOS_HMC5883_ReadMag(values); + float mags[3] = {(float) values[1] * mag_scale[0] - mag_bias[0], + (float) values[0] * mag_scale[1] - mag_bias[1], + -(float) values[2] * mag_scale[2] - mag_bias[2]}; + if (rotate) { + float mag_out[3]; + rot_mult(R, mags, mag_out); + mag.x = mag_out[0]; + mag.y = mag_out[1]; + mag.z = mag_out[2]; + } else { + mag.x = mags[0]; + mag.y = mags[1]; + mag.z = mags[2]; + } + MagnetometerSet(&mag); + mag_update_time = PIOS_DELAY_GetRaw(); + } +#endif PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); From d45fae138048af08e1ffba2f31b7560bde5c98bf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 01:55:55 -0500 Subject: [PATCH 081/508] For now disable the bootloader updaters from being built with packaging. They aren't packaged into the distributable and the bu_revolution breaks. --- package/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package/Makefile b/package/Makefile index 0ea156682..713ac0416 100644 --- a/package/Makefile +++ b/package/Makefile @@ -95,7 +95,7 @@ $(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(PACKAGE_LBL),,,$( $(eval $(call INSTALL_TEMPLATE,all_bu,all_bl,$(BU_DIR),,-$(PACKAGE_LBL),,,$(BU_TARGETS),install)) # Order-only dependencies -package_flight: | all_fw all_bu +package_flight: | all_fw package_ground: | ground_package From 8ded4618efea71d68f0f6e15c823c1314bc77ecd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 12:28:59 -0500 Subject: [PATCH 082/508] Only perform six point calibration on the mag. This code is #ifdef'd out because we might still want the option or need it for factory calibration. I usually find the accel scale is reproducibly at 0.98. --- .../src/plugins/config/configrevowidget.cpp | 28 ++++++++++++++----- 1 file changed, 21 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 45d400852..009df4d8e 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -52,6 +52,7 @@ #define sign(x) ((x < 0) ? -1 : 1) +#define SIX_POINT_CAL_ACCEL 0 const double ConfigRevoWidget::maxVarValue = 0.1; // ***************** @@ -360,18 +361,17 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) { QMutexLocker lock(&attitudeRawUpdateLock); - qDebug() << "Data"; // This is necessary to prevent a race condition on disconnect signal and another update if (collectingData == true) { - qDebug() << "Collecting"; if( obj->getObjID() == Accels::OBJID ) { - qDebug() << "Accels"; +#ifdef SIX_POINT_CAL_ACCEL Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); accel_accum_x.append(accelsData.x); accel_accum_y.append(accelsData.y); accel_accum_z.append(accelsData.z); +#endif } else if( obj->getObjID() == Magnetometer::OBJID ) { qDebug() << "Mag"; Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); @@ -385,7 +385,11 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) } } +#ifdef SIX_POINT_CAL_ACCEL if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { +#else + if(mag_accum_x.size() >= 20 && collectingData == true) { +#endif collectingData = false; Accels * accels = Accels::GetInstance(getObjectManager()); @@ -396,10 +400,11 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); m_ui->sixPointsSave->setEnabled(true); - +#ifdef SIX_POINT_CAL_ACCEL accel_data_x[position] = listMean(accel_accum_x); accel_data_y[position] = listMean(accel_accum_y); accel_data_z[position] = listMean(accel_accum_z); +#endif mag_data_x[position] = listMean(mag_accum_x); mag_data_y[position] = listMean(mag_accum_y); mag_data_z[position] = listMean(mag_accum_z); @@ -580,6 +585,7 @@ void ConfigRevoWidget::computeScaleBias() RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); +#ifdef SIX_POINT_CAL_ACCEL // Calibration accel SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); @@ -589,6 +595,7 @@ void ConfigRevoWidget::computeScaleBias() revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; +#endif // Calibration mag Be_lenght = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); @@ -604,7 +611,11 @@ void ConfigRevoWidget::computeScaleBias() revoCalibration->setData(revoCalibrationData); position = -1; //set to run again +#ifdef SIX_POINT_CAL_ACCEL m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); +#else + m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); +#endif } @@ -632,6 +643,7 @@ void ConfigRevoWidget::sixPointCalibrationMode() return; } +#ifdef SIX_POINT_CAL_ACCEL // Calibration accel revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = 1; revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = 1; @@ -640,6 +652,11 @@ void ConfigRevoWidget::sixPointCalibrationMode() revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); +#endif + // Calibration mag revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = 1; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = 1; @@ -655,9 +672,6 @@ void ConfigRevoWidget::sixPointCalibrationMode() gyro_accum_x.clear(); gyro_accum_y.clear(); gyro_accum_z.clear(); - accel_accum_x.clear(); - accel_accum_y.clear(); - accel_accum_z.clear(); mag_accum_x.clear(); mag_accum_y.clear(); mag_accum_z.clear(); From b074b1f71282b14652f855a1cc227d21f3ed1e0f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 12:30:07 -0500 Subject: [PATCH 083/508] Work on the OSX packaging to get it working for revo and to package OSG. --- package/osx/libraries | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/package/osx/libraries b/package/osx/libraries index d6c559682..f1d91b465 100755 --- a/package/osx/libraries +++ b/package/osx/libraries @@ -5,14 +5,16 @@ PLUGINS="${APP}/Contents/Plugins" OP_PLUGINS="${APP}/Contents/Plugins/OpenPilot" QT_LIBS="QtDeclarative QtXmlPatterns QtGui QtTest QtCore QtSvg QtSql QtOpenGL QtNetwork QtXml QtDBus QtScript phonon" QT_DIR=$(otool -L "${APP}/Contents/MacOS/OpenPilot GCS" | sed -n -e 's/\/QtCore\.framework.*//p' | sed -n -E 's:^.::p') -QT_EXTRA="accessible/libqtaccessiblewidgets.dylib bearer/libqgenericbearer.dylib codecs/libqcncodecs.dylib codecs/libqjpcodecs.dylib codecs/libqkrcodecs.dylib codecs/libqtwcodecs.dylib graphicssystems/libqtracegraphicssystem.dylib imageformats/libqgif.dylib imageformats/libqico.dylib imageformats/libqjpeg.dylib imageformats/libqmng.dylib imageformats/libqtiff.dylib imageformats/libqsvg.dylib qmltooling/libqmldbg_inspector.dylib qmltooling/libqmldbg_tcp.dylib" +QT_EXTRA="accessible/libqtaccessiblewidgets.dylib bearer/libqgenericbearer.dylib codecs/libqcncodecs.dylib codecs/libqjpcodecs.dylib codecs/libqkrcodecs.dylib codecs/libqtwcodecs.dylib graphicssystems/libqtracegraphicssystem.dylib imageformats/libqgif.dylib imageformats/libqico.dylib imageformats/libqjpeg.dylib imageformats/libqmng.dylib imageformats/libqtiff.dylib imageformats/libqsvg.dylib qmltooling/libqmldbg_inspector.dylib qmltooling/libqmldbg_tcp.dylib graphicssystems/libqglgraphicssystem.dylib sqldrivers/libqsqlodbc.dylib sqldrivers/libqsqlpsql.dylib sqldrivers/libqsqlite.dylib imageformats/libqtga.dylib iconengines/libqsvgicon.dylib" +OSG_EXTRA="libosgViewer.90.dylib" echo "Qt library directory is \"${QT_DIR}\"" -echo "Processing Qt libraries in $1" +echo "Running macdeployqt" macdeployqt "${APP}" +echo "Processing Qt libraries in $1" for f in "${PLUGINS}/"*.dylib "${OP_PLUGINS}/"*.dylib do for g in $QT_LIBS @@ -24,7 +26,7 @@ do done done - +echo "Copying other libraries that were missed" # should be redundant but some libs missed by main app and macdeployqt for f in ${QT_LIBS} do @@ -76,6 +78,18 @@ install_name_tool -id \ "${APP}/Contents/Frameworks/SDL.framework/Versions/A/SDL" # deleting unnecessary files + +echo "Copying OSG libraries" +for f in ${OSG_EXTRA} +do + echo "Copying library ${f} + cp /usr/local/lib/{$f} "${APP}/Contents/Plugins/${f}" + echo "Changing package identification of ${f} + install_name_tool -id \ + @executable_path/../Frameworks/SDL.framework/Versions/A/SDL \ + "${APP}/Contents/Frameworks/SDL.framework/Versions/A/SDL" +done + echo "Deleting unnecessary files" find "${APP}/Contents/Frameworks" -iname "current" -exec rm -rf \{\} \; find "${APP}/Contents/Frameworks" -iname "4.0" -exec rm -rf \{\} \; From 49b51163bcdba53fce86bdc5d3642b2125e51f6e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 12:37:17 -0500 Subject: [PATCH 084/508] Rename method and UI in revo calibration to fit new uavos and stop referring to things as AHRS --- .../src/plugins/config/configrevowidget.cpp | 54 +++++++++---------- .../src/plugins/config/configrevowidget.h | 5 +- .../src/plugins/config/revosensors.ui | 10 ++-- 3 files changed, 34 insertions(+), 35 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 009df4d8e..23384e26a 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -87,16 +87,16 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); // Initialization of the Revo sensor noise bargraph graph - m_ui->ahrsBargraph->setScene(new QGraphicsScene(this)); + m_ui->sensorsBargraph->setScene(new QGraphicsScene(this)); QSvgRenderer *renderer = new QSvgRenderer(); - ahrsbargraph = new QGraphicsSvgItem(); + sensorsBargraph = new QGraphicsSvgItem(); renderer->load(QString(":/configgadget/images/ahrs-calib.svg")); - ahrsbargraph->setSharedRenderer(renderer); - ahrsbargraph->setElementId("background"); - ahrsbargraph->setObjectName("background"); - m_ui->ahrsBargraph->scene()->addItem(ahrsbargraph); - m_ui->ahrsBargraph->setSceneRect(ahrsbargraph->boundingRect()); + sensorsBargraph->setSharedRenderer(renderer); + sensorsBargraph->setElementId("background"); + sensorsBargraph->setObjectName("background"); + m_ui->sensorsBargraph->scene()->addItem(sensorsBargraph); + m_ui->sensorsBargraph->setSceneRect(sensorsBargraph->boundingRect()); // Initialize the 9 bargraph values: @@ -113,7 +113,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : accel_x = new QGraphicsSvgItem(); accel_x->setSharedRenderer(renderer); accel_x->setElementId("accel_x"); - m_ui->ahrsBargraph->scene()->addItem(accel_x); + m_ui->sensorsBargraph->scene()->addItem(accel_x); accel_x->setPos(startX, startY); accel_x->setTransform(QTransform::fromScale(1,0),true); @@ -124,7 +124,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : accel_y = new QGraphicsSvgItem(); accel_y->setSharedRenderer(renderer); accel_y->setElementId("accel_y"); - m_ui->ahrsBargraph->scene()->addItem(accel_y); + m_ui->sensorsBargraph->scene()->addItem(accel_y); accel_y->setPos(startX,startY); accel_y->setTransform(QTransform::fromScale(1,0),true); @@ -135,7 +135,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : accel_z = new QGraphicsSvgItem(); accel_z->setSharedRenderer(renderer); accel_z->setElementId("accel_z"); - m_ui->ahrsBargraph->scene()->addItem(accel_z); + m_ui->sensorsBargraph->scene()->addItem(accel_z); accel_z->setPos(startX,startY); accel_z->setTransform(QTransform::fromScale(1,0),true); @@ -146,7 +146,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : gyro_x = new QGraphicsSvgItem(); gyro_x->setSharedRenderer(renderer); gyro_x->setElementId("gyro_x"); - m_ui->ahrsBargraph->scene()->addItem(gyro_x); + m_ui->sensorsBargraph->scene()->addItem(gyro_x); gyro_x->setPos(startX,startY); gyro_x->setTransform(QTransform::fromScale(1,0),true); @@ -157,7 +157,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : gyro_y = new QGraphicsSvgItem(); gyro_y->setSharedRenderer(renderer); gyro_y->setElementId("gyro_y"); - m_ui->ahrsBargraph->scene()->addItem(gyro_y); + m_ui->sensorsBargraph->scene()->addItem(gyro_y); gyro_y->setPos(startX,startY); gyro_y->setTransform(QTransform::fromScale(1,0),true); @@ -169,7 +169,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : gyro_z = new QGraphicsSvgItem(); gyro_z->setSharedRenderer(renderer); gyro_z->setElementId("gyro_z"); - m_ui->ahrsBargraph->scene()->addItem(gyro_z); + m_ui->sensorsBargraph->scene()->addItem(gyro_z); gyro_z->setPos(startX,startY); gyro_z->setTransform(QTransform::fromScale(1,0),true); @@ -180,7 +180,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : mag_x = new QGraphicsSvgItem(); mag_x->setSharedRenderer(renderer); mag_x->setElementId("mag_x"); - m_ui->ahrsBargraph->scene()->addItem(mag_x); + m_ui->sensorsBargraph->scene()->addItem(mag_x); mag_x->setPos(startX,startY); mag_x->setTransform(QTransform::fromScale(1,0),true); @@ -191,7 +191,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : mag_y = new QGraphicsSvgItem(); mag_y->setSharedRenderer(renderer); mag_y->setElementId("mag_y"); - m_ui->ahrsBargraph->scene()->addItem(mag_y); + m_ui->sensorsBargraph->scene()->addItem(mag_y); mag_y->setPos(startX,startY); mag_y->setTransform(QTransform::fromScale(1,0),true); @@ -202,7 +202,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : mag_z = new QGraphicsSvgItem(); mag_z->setSharedRenderer(renderer); mag_z->setElementId("mag_z"); - m_ui->ahrsBargraph->scene()->addItem(mag_z); + m_ui->sensorsBargraph->scene()->addItem(mag_z); mag_z->setPos(startX,startY); mag_z->setTransform(QTransform::fromScale(1,0),true); @@ -213,8 +213,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : Q_ASSERT(revoCalibration); connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); - connect(m_ui->ahrsSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); - connect(m_ui->ahrsSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); + connect(m_ui->revoCalSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); + connect(m_ui->revoCalSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); @@ -230,7 +230,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); // Connect the help button - connect(m_ui->ahrsHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + connect(m_ui->Help, SIGNAL(clicked()), this, SLOT(openHelp())); } ConfigRevoWidget::~ConfigRevoWidget() @@ -244,15 +244,15 @@ void ConfigRevoWidget::showEvent(QShowEvent *event) Q_UNUSED(event) // Thit fitInView method should only be called now, once the // widget is shown, otherwise it cannot compute its values and - // the result is usually a ahrsbargraph that is way too small. - m_ui->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); + // the result is usually a sensorsBargraph that is way too small. + m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); } void ConfigRevoWidget::resizeEvent(QResizeEvent *event) { Q_UNUSED(event) - m_ui->ahrsBargraph->fitInView(ahrsbargraph, Qt::KeepAspectRatio); + m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); } @@ -293,13 +293,13 @@ void ConfigRevoWidget::launchAccelBiasCalibration() // Now connect to the accels and mag updates, gather for 100 samples collectingData = true; - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelBiasattitudeRawUpdated(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelBiasData(UAVObject*))); } /** Updates the accel bias raw values */ -void ConfigRevoWidget::accelBiasattitudeRawUpdated(UAVObject *obj) +void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) { Q_UNUSED(obj); @@ -318,7 +318,7 @@ void ConfigRevoWidget::accelBiasattitudeRawUpdated(UAVObject *obj) if(accel_accum_x.size() >= 100 && collectingData == true) { collectingData = false; - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelBiasattitudeRawUpdated(UAVObject*))); + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelBiasData(UAVObject*))); m_ui->accelBiasStart->setEnabled(true); RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); @@ -359,7 +359,7 @@ void ConfigRevoWidget::incrementProgress() void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) { - QMutexLocker lock(&attitudeRawUpdateLock); + QMutexLocker lock(&sensorsUpdateLock); // This is necessary to prevent a race condition on disconnect signal and another update if (collectingData == true) { @@ -447,7 +447,7 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) */ void ConfigRevoWidget::savePositionData() { - QMutexLocker lock(&attitudeRawUpdateLock); + QMutexLocker lock(&sensorsUpdateLock); m_ui->sixPointsSave->setEnabled(false); accel_accum_x.clear(); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 82d7025fc..b1abe2202 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -68,7 +68,7 @@ private: QGraphicsSvgItem *mag_x; QGraphicsSvgItem *mag_y; QGraphicsSvgItem *mag_z; - QMutex attitudeRawUpdateLock; + QMutex sensorsUpdateLock; double maxBarHeight; int phaseCounter; int progressBarIndex; @@ -100,14 +100,13 @@ private slots: void incrementProgress(); virtual void refreshValues(); - //void ahrsSettingsRequest(); void SettingsToRAM(); void SettingsToFlash(); void savePositionData(); void computeScaleBias(); void sixPointCalibrationMode(); void sensorsUpdated(UAVObject * obj); - void accelBiasattitudeRawUpdated(UAVObject*); + void doGetAccelBiasData(UAVObject*); protected: void showEvent(QShowEvent *event); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index e92d09d7b..e30106373 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -51,7 +51,7 @@ - #1: Multi-Point Calibration + #1: Magnetometer calibrtion @@ -157,7 +157,7 @@ - + These are the sensor variance values computed by the AHRS. @@ -630,7 +630,7 @@ new home location unless it is in indoor mode. - + 0 @@ -673,7 +673,7 @@ new home location unless it is in indoor mode. - + Save settings to the board (RAM only). @@ -686,7 +686,7 @@ specific calibration button on top of the screen. - + Send settings to the board, and save to the non-volatile memory. From 7c8700b4e5d970f1e77dbf90618c8a9195dd75d7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 13:01:41 -0500 Subject: [PATCH 085/508] Suppress a warning and fix indentation in configgadgetwidget --- .../src/plugins/config/configgadgetwidget.cpp | 23 +++++++++---------- 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index c12dbaee8..9bf8bed0a 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -216,19 +216,18 @@ void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) /*! \brief Called by updates to @PipXStatus */ -void ConfigGadgetWidget::updatePipXStatus(UAVObject *object) +void ConfigGadgetWidget::updatePipXStatus(UAVObject *) { - - // Restart the disconnection timer. - pipxTimeout->start(5000); - if (!pipxConnected) - { - qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; - QWidget *qwd = new ConfigPipXtremeWidget(this); - ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); - ftw->setCurrentIndex(ConfigGadgetWidget::pipxtreme); - pipxConnected = true; - } + // Restart the disconnection timer. + pipxTimeout->start(5000); + if (!pipxConnected) + { + qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; + QWidget *qwd = new ConfigPipXtremeWidget(this); + ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); + ftw->setCurrentIndex(ConfigGadgetWidget::pipxtreme); + pipxConnected = true; + } } void ConfigGadgetWidget::onPipxtremeDisconnect() { From 7f15e87890ee3098accf2b230031ceac393ff120 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 13:08:04 -0500 Subject: [PATCH 086/508] Make revo calibration UI use teh configtaskwidget system --- .../src/plugins/config/configrevowidget.cpp | 59 +++---------------- .../src/plugins/config/configrevowidget.h | 8 +-- .../src/plugins/config/revosensors.ui | 12 ++++ 3 files changed, 22 insertions(+), 57 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 23384e26a..21d5e01cd 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -71,11 +71,14 @@ public: ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : ConfigTaskWidget(parent), collectingData(false), - position(-1), - m_ui(new Ui_RevoSensorsWidget()) + position(-1) { + m_ui = new Ui_RevoSensorsWidget(); m_ui->setupUi(this); + addUAVObject("RevoCalibration"); + autoLoadWidgets(); + // Initialization of the Paper plane widget m_ui->sixPointsHelp->setScene(new QGraphicsScene(this)); @@ -209,10 +212,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Connect the signals connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - connect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); - connect(m_ui->revoCalSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); connect(m_ui->revoCalSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); @@ -221,16 +220,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Leave this timer permanently connected. The timer itself is started and stopped. connect(&progressBarTimer, SIGNAL(timeout()), this, SLOT(incrementProgress())); - // Order is important: 1st request the settings (it will also enable the controls) - // then explicitely disable them. They will be re-enabled right afterwards by the - // configgadgetwidget if the autopilot is actually connected. - refreshValues(); - // when the AHRS Widget is instanciated, the autopilot is always connected // enableControls(false); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - // Connect the help button - connect(m_ui->Help, SIGNAL(clicked()), this, SLOT(openHelp())); } ConfigRevoWidget::~ConfigRevoWidget() @@ -257,12 +247,6 @@ void ConfigRevoWidget::resizeEvent(QResizeEvent *event) } -void ConfigRevoWidget::enableControls(bool enable) -{ - //m_ui->ahrsSettingsSaveRAM->setEnabled(enable); - m_ui->ahrsSettingsSaveSD->setEnabled(enable); -} - /** Starts an accelerometer bias calibration. */ @@ -752,9 +736,10 @@ void ConfigRevoWidget::drawVariancesGraph() } /** - Request current settings from the AHRS + * Called by the ConfigTaskWidget parent when RevoCalibration is updated + * to update the UI */ -void ConfigRevoWidget::refreshValues() +void ConfigRevoWidget::refreshWidgetsValues(UAVObject *) { drawVariancesGraph(); @@ -766,34 +751,6 @@ void ConfigRevoWidget::refreshValues() m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); } - -/** - Save current settings to RAM - */ -void ConfigRevoWidget::SettingsToRAM() -{ - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - revoCalibration->updated(); -} - -/** -Save Revo calibration settings to flash - */ -void ConfigRevoWidget::SettingsToFlash() -{ - SettingsToRAM(); - - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - saveObjectToSD(revoCalibration); -} - -void ConfigRevoWidget::openHelp() -{ - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Revo+Configuration", QUrl::StrictMode) ); -} - /** @} @} diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index b1abe2202..0d19f273a 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -54,11 +54,10 @@ public: private: void drawVariancesGraph(); void displayPlane(QString elementID); - virtual void enableControls(bool enable); Ui_RevoSensorsWidget *m_ui; QGraphicsSvgItem *paperplane; - QGraphicsSvgItem *ahrsbargraph; + QGraphicsSvgItem *sensorsBargraph; QGraphicsSvgItem *accel_x; QGraphicsSvgItem *accel_y; QGraphicsSvgItem *accel_z; @@ -95,13 +94,10 @@ private: int position; private slots: - void openHelp(); void launchAccelBiasCalibration(); void incrementProgress(); - virtual void refreshValues(); - void SettingsToRAM(); - void SettingsToFlash(); + virtual void refreshWidgetsValues(UAVObject * obj=NULL); void savePositionData(); void computeScaleBias(); void sixPointCalibrationMode(); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index e30106373..914655724 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -670,6 +670,12 @@ new home location unless it is in indoor mode. true + + + button:help + url:http://wiki.openpilot.org/display/Doc/Revo+Configuration + + @@ -683,6 +689,9 @@ specific calibration button on top of the screen. Apply + + button:apply + @@ -696,6 +705,9 @@ specific calibration button on top of the screen. false + + button:save + From d94ab30616ef8e43e21b2778ff16ac56a1bde4e7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 13:19:17 -0500 Subject: [PATCH 087/508] Make sure we don't use null pointers when refreshing the revo sensor bar graphs --- .../src/plugins/config/configrevowidget.cpp | 37 +++++++++++++------ 1 file changed, 25 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 21d5e01cd..41311bda8 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -76,9 +76,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : m_ui = new Ui_RevoSensorsWidget(); m_ui->setupUi(this); - addUAVObject("RevoCalibration"); - autoLoadWidgets(); - // Initialization of the Paper plane widget m_ui->sixPointsHelp->setScene(new QGraphicsScene(this)); @@ -209,6 +206,11 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : mag_z->setPos(startX,startY); mag_z->setTransform(QTransform::fromScale(1,0),true); + // Must set up the UI (above) before setting up the UAVO mappings or refreshWidgetValues + // will be dealing with some null pointers + addUAVObject("RevoCalibration"); + autoLoadWidgets(); + // Connect the signals connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); @@ -708,31 +710,42 @@ void ConfigRevoWidget::drawVariancesGraph() { RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); + if(!revoCalibration) + return; RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); // The expected range is from 1E-6 to 1E-1 double steps = 6; // 6 bars on the graph float accel_x_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_X])); - accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); + if(accel_x) + accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); float accel_y_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Y])); - accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); + if(accel_y) + accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); float accel_z_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Z])); - accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); + if(accel_z) + accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); float gyro_x_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_X])); - gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); + if(gyro_x) + gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); float gyro_y_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Y])); - gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); + if(gyro_y) + gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); float gyro_z_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Z])); - gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); + if(gyro_z) + gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); // Scale by 1e-3 because mag vars are much higher. float mag_x_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_X])); - mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); + if(mag_x) + mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); float mag_y_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Y])); - mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); + if(mag_y) + mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); float mag_z_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Z])); - mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); + if(mag_z) + mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); } /** From 28b967689f211f8bc396b59fda15d281d7f60e74 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 13:22:39 -0500 Subject: [PATCH 088/508] Remove some debugging output from configTaskWidget. In the case of the sensor calibration which doesn't have any fields associated this caused a null pointer crash and wasn't useful anyway. --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7fb8d70c7..2681462e7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -696,14 +696,6 @@ void ConfigTaskWidget::autoLoadWidgets() } refreshWidgetsValues(); forceShadowUpdates(); - foreach(objectToWidget * ow,objOfInterest) - { - qDebug()<<"Master:"<widget->objectName(); - foreach(shadow * sh,ow->shadowsList) - { - qDebug()<<"Child"<widget->objectName(); - } - } } /** * Adds a widget to a list of default/reload groups From fc6f0f5d4d4e900c50f867617011eeed4c745955 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 14:52:34 -0500 Subject: [PATCH 089/508] Actually disable the 6 point calibration define --- .../openpilotgcs/src/plugins/config/configrevowidget.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 41311bda8..9d476b1de 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -52,7 +52,9 @@ #define sign(x) ((x < 0) ? -1 : 1) -#define SIX_POINT_CAL_ACCEL 0 +// Uncomment this to enable 6 point calibration on the accels +//#define SIX_POINT_CAL_ACCEL + const double ConfigRevoWidget::maxVarValue = 0.1; // ***************** @@ -213,9 +215,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Connect the signals connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); - - connect(m_ui->revoCalSettingsSaveRAM, SIGNAL(clicked()), this, SLOT(SettingsToRAM())); - connect(m_ui->revoCalSettingsSaveSD, SIGNAL(clicked()), this, SLOT(SettingsToFlash())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); From f07e1fc4e12acdace2c95c8f477d97d8f0e84734 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 18:09:10 -0500 Subject: [PATCH 090/508] Separately store initial meta data for accel and mag --- .../src/plugins/config/configrevowidget.cpp | 20 +++++++++---------- .../src/plugins/config/configrevowidget.h | 6 +++++- 2 files changed, 15 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 9d476b1de..c0ab2b26b 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -267,11 +267,11 @@ void ConfigRevoWidget::launchAccelBiasCalibration() accel_accum_y.clear(); accel_accum_z.clear(); - /* Need to get as many AttitudeRaw updates as possible */ + /* Need to get as many accel updates as possible */ Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - initialMdata = accels->getMetadata(); - UAVObject::Metadata mdata = initialMdata; + initialAccelsMdata = accels->getMetadata(); + UAVObject::Metadata mdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); @@ -318,7 +318,7 @@ void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); - accels->setMetadata(initialMdata); + accels->setMetadata(initialAccelsMdata); } } @@ -358,7 +358,6 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) accel_accum_z.append(accelsData.z); #endif } else if( obj->getObjID() == Magnetometer::OBJID ) { - qDebug() << "Mag"; Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); Magnetometer::DataFields magData = mag->getData(); @@ -421,8 +420,8 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) m_ui->sixPointsSave->setEnabled(false); /* Cleanup original settings */ - accels->setMetadata(initialMdata); - mag->setMetadata(initialMdata); + accels->setMetadata(initialAccelsMdata); + mag->setMetadata(initialMagMdata); } } } @@ -667,13 +666,14 @@ void ConfigRevoWidget::sixPointCalibrationMode() Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - initialMdata = accels->getMetadata(); - UAVObject::Metadata mdata = initialMdata; + initialAccelsMdata = accels->getMetadata(); + UAVObject::Metadata mdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); - mdata = mag->getMetadata(); + initialMagMdata = mag->getMetadata(); + mdata = initialMagMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; mag->setMetadata(mdata); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 0d19f273a..aaaa39880 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -90,7 +90,11 @@ private: double accel_data_x[6], accel_data_y[6], accel_data_z[6]; double mag_data_x[6], mag_data_y[6], mag_data_z[6]; - UAVObject::Metadata initialMdata; + UAVObject::Metadata initialAccelsMdata; + UAVObject::Metadata initialGyrosMdata; + UAVObject::Metadata initialMagMdata; + UAVObject::Metadata initialBaroMdata; + int position; private slots: From 293a2ee573d60358f22f1cb09857413254525c7f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 18:14:20 -0500 Subject: [PATCH 091/508] Rename some of the revo calibration methods --- .../src/plugins/config/configrevowidget.cpp | 31 ++++++++++++++----- .../src/plugins/config/configrevowidget.h | 4 +-- .../src/plugins/config/revosensors.ui | 4 +-- 3 files changed, 28 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index c0ab2b26b..f8703e93d 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -215,7 +215,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Connect the signals connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); - connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(sixPointCalibrationMode())); + connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibration())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); // Leave this timer permanently connected. The timer itself is started and stopped. @@ -342,7 +342,7 @@ void ConfigRevoWidget::incrementProgress() } } -void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) +void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) { QMutexLocker lock(&sensorsUpdateLock); @@ -380,8 +380,8 @@ void ConfigRevoWidget::sensorsUpdated(UAVObject * obj) Q_ASSERT(accels); Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); - disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); m_ui->sixPointsSave->setEnabled(true); #ifdef SIX_POINT_CAL_ACCEL @@ -451,8 +451,8 @@ void ConfigRevoWidget::savePositionData() Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(sensorsUpdated(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(sensorsUpdated(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); m_ui->sixPointCalibInstructions->append("Hold..."); } @@ -606,7 +606,7 @@ void ConfigRevoWidget::computeScaleBias() /** Six point calibration mode */ -void ConfigRevoWidget::sixPointCalibrationMode() +void ConfigRevoWidget::doStartSixPointCalibration() { RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); @@ -747,6 +747,23 @@ void ConfigRevoWidget::drawVariancesGraph() mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); } +/** + * Connect sensor updates and timeout for measuring the noise + */ +void ConfigRevoWidget::doStartNoiseMeasurement() +{ + +} + +/** + * Called when any of the sensors are updated. Stores the sample for measuring the + * variance at the end + */ +void ConfigRevoWidget::doGetNoiseSample(UAVObject *) +{ + +} + /** * Called by the ConfigTaskWidget parent when RevoCalibration is updated * to update the UI diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index aaaa39880..865cec32b 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -104,8 +104,8 @@ private slots: virtual void refreshWidgetsValues(UAVObject * obj=NULL); void savePositionData(); void computeScaleBias(); - void sixPointCalibrationMode(); - void sensorsUpdated(UAVObject * obj); + void doStartSixPointCalibration(); + void doGetSixPointCalibrationMeasurement(UAVObject * obj); void doGetAccelBiasData(UAVObject*); protected: diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 914655724..7b1199003 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -174,7 +174,7 @@ Tip: lower is better! - + false @@ -189,7 +189,7 @@ Hint: run this with engines at cruising speed. - + true From ce487c9b0af221ceb9bd17cff2ea27f7c8127121 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 21:15:46 -0500 Subject: [PATCH 092/508] Fix the bias calculation for revo accels --- .../openpilotgcs/src/plugins/config/configrevowidget.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index f8703e93d..5864aa8ea 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -311,9 +311,9 @@ void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] -= listMean(accel_accum_x); - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] -= listMean(accel_accum_y); - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] -= GRAVITY + listMean(accel_accum_z); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] += listMean(accel_accum_x); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] += listMean(accel_accum_y); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += ( listMean(accel_accum_z) + GRAVITY ); revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); @@ -685,7 +685,6 @@ void ConfigRevoWidget::doStartSixPointCalibration() m_ui->sixPointsStart->setEnabled(false); m_ui->sixPointsSave->setEnabled(true); position = 0; - qDebug() << "Starting"; } From 03705771dd0da8a09225901e635e29a45f7c73a2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 21:26:24 -0500 Subject: [PATCH 093/508] Get the sensor noise measurement working again, but through GCS now --- .../src/plugins/config/configrevowidget.cpp | 132 +++++++++++++++++- .../src/plugins/config/configrevowidget.h | 6 + .../src/plugins/config/revosensors.ui | 2 +- .../src/plugins/opmap/pathcompiler.cpp | 1 - .../uavobjectwidgetutils/configtaskwidget.cpp | 23 +++ .../uavobjectwidgetutils/configtaskwidget.h | 1 + 6 files changed, 159 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 5864aa8ea..75e7b13dd 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -217,6 +217,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibration())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); + connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement())); // Leave this timer permanently connected. The timer itself is started and stopped. connect(&progressBarTimer, SIGNAL(timeout()), this, SLOT(incrementProgress())); @@ -327,8 +328,8 @@ void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) */ void ConfigRevoWidget::incrementProgress() { - m_ui->calibProgress->setValue(m_ui->calibProgress->value()+1); - if (m_ui->calibProgress->value() >= m_ui->calibProgress->maximum()) { + m_ui->noiseMeasurementProgress->setValue(m_ui->noiseMeasurementProgress->value()+1); + if (m_ui->noiseMeasurementProgress->value() >= m_ui->noiseMeasurementProgress->maximum()) { progressBarTimer.stop(); RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); @@ -751,16 +752,139 @@ void ConfigRevoWidget::drawVariancesGraph() */ void ConfigRevoWidget::doStartNoiseMeasurement() { + QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + mag_accum_x.clear(); + mag_accum_y.clear(); + mag_accum_z.clear(); + + /* Need to get as many accel, mag and gyro updates as possible */ + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Q_ASSERT(gyros); + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + + UAVObject::Metadata mdata; + + initialAccelsMdata = accels->getMetadata(); + mdata = initialAccelsMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + accels->setMetadata(mdata); + + initialGyrosMdata = gyros->getMetadata(); + mdata = initialGyrosMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + gyros->setMetadata(mdata); + + initialMagMdata = mag->getMetadata(); + mdata = initialMagMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + mag->setMetadata(mdata); + + /* Connect for updates */ + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); } /** * Called when any of the sensors are updated. Stores the sample for measuring the * variance at the end */ -void ConfigRevoWidget::doGetNoiseSample(UAVObject *) +void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) { + QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); + Q_ASSERT(obj); + + switch(obj->getObjID()) { + case Gyros::OBJID: + { + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Q_ASSERT(gyros); + Gyros::DataFields gyroData = gyros->getData(); + gyro_accum_x.append(gyroData.x); + gyro_accum_y.append(gyroData.y); + gyro_accum_z.append(gyroData.z); + break; + } + case Accels::OBJID: + { + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Accels::DataFields accelsData = accels->getData(); + accel_accum_x.append(accelsData.x); + accel_accum_y.append(accelsData.y); + accel_accum_z.append(accelsData.z); + break; + } + case Magnetometer::OBJID: + { + Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mags); + Magnetometer::DataFields magData = mags->getData(); + mag_accum_x.append(magData.x); + mag_accum_y.append(magData.y); + mag_accum_z.append(magData.z); + break; + } + default: + Q_ASSERT(0); + } + + float p1 = (float) mag_accum_x.length() / (float) NOISE_SAMPLES; + float p2 = (float) gyro_accum_x.length() / (float) NOISE_SAMPLES; + float p3 = (float) accel_accum_x.length() / (float) NOISE_SAMPLES; + + float prog = (p1 < p2) ? p1 : p2; + prog = (prog < p3) ? prog : p3; + + m_ui->noiseMeasurementProgress->setValue(prog * 100); + + if(mag_accum_x.length() >= NOISE_SAMPLES && + gyro_accum_x.length() >= NOISE_SAMPLES && + accel_accum_x.length() >= NOISE_SAMPLES) { + + // No need to for more updates + Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); + Accels * accels = Accels::GetInstance(getObjectManager()); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + disconnect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + disconnect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + disconnect(mags, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + if(revoCalibration) { + RevoCalibration::DataFields revoCalData = revoCalibration->getData(); + revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_X] = listVar(accel_accum_x); + revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_Y] = listVar(accel_accum_y); + revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_Z] = listVar(accel_accum_z); + revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_X] = listVar(gyro_accum_x); + revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_Y] = listVar(gyro_accum_y); + revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_Z] = listVar(gyro_accum_z); + revoCalData.mag_var[RevoCalibration::MAG_BIAS_X] = listVar(mag_accum_x); + revoCalData.mag_var[RevoCalibration::MAG_BIAS_Y] = listVar(mag_accum_y); + revoCalData.mag_var[RevoCalibration::MAG_BIAS_Z] = listVar(mag_accum_z); + revoCalibration->setData(revoCalData); + } + } } /** @@ -771,7 +895,7 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *) { drawVariancesGraph(); - m_ui->ahrsCalibStart->setEnabled(true); + m_ui->noiseMeasurementStart->setEnabled(true); m_ui->sixPointsStart->setEnabled(true); m_ui->accelBiasStart->setEnabled(true); m_ui->startDriftCalib->setEnabled(true); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 865cec32b..6822eb2ce 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -97,6 +97,8 @@ private: int position; + static const int NOISE_SAMPLES = 100; + private slots: void launchAccelBiasCalibration(); void incrementProgress(); @@ -108,6 +110,10 @@ private slots: void doGetSixPointCalibrationMeasurement(UAVObject * obj); void doGetAccelBiasData(UAVObject*); + // Slots for measuring the sensor noise + void doStartNoiseMeasurement(); + void doGetNoiseSample(UAVObject *); + protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 7b1199003..b272f4614 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -194,7 +194,7 @@ Hint: run this with engines at cruising speed. true - 15 + 100 0 diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index f8d4dca1b..1bc82c5d7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -44,7 +44,6 @@ PathCompiler::PathCompiler(QObject *parent) : /* Connect the object updates */ int numWaypoints = getObjectManager()->getNumInstances(Waypoint::OBJID); for (int i = 0; i < numWaypoints; i++) { - qDebug() << "Registering waypoint" << i; Waypoint *waypoint = Waypoint::GetInstance(getObjectManager(), i); Q_ASSERT(waypoint); if(waypoint) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 2681462e7..6a540f944 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -201,6 +201,7 @@ UAVObjectManager* ConfigTaskWidget::getObjectManager() { Q_ASSERT(objMngr); return objMngr; } + /** * Utility function which calculates the Mean value of a list of values * @param list list of double values @@ -214,6 +215,28 @@ double ConfigTaskWidget::listMean(QList list) return accum / list.size(); } +/** + * Utility function which calculates the Variance value of a list of values + * @param list list of double values + * @returns Variance of the list of parameter values + */ +double ConfigTaskWidget::listVar(QList list) +{ + double mean_accum = 0; + double var_accum = 0; + double mean; + + for(int i = 0; i < list.size(); i++) + mean_accum += list[i]; + mean = mean_accum / list.size(); + + for(int i = 0; i < list.size(); i++) + var_accum += (list[i] - mean) * (list[i] - mean); + + // Use unbiased estimator + return var_accum / (list.size() - 1); +} + // ************************************ // telemetry start/stop connect/disconnect signals diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 76d6b55bd..8d9d66165 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -92,6 +92,7 @@ public: void saveObjectToSD(UAVObject *obj); UAVObjectManager* getObjectManager(); static double listMean(QList list); + static double listVar(QList list); void addUAVObject(QString objectName); void addWidget(QWidget * widget); From 70606a46a101f90a30a4a7a64079c4e9cbc166cb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 23:07:23 -0500 Subject: [PATCH 094/508] Include initial gyro bias calibration into the level calibration of revo like it is with CC. --- flight/Modules/Sensors/sensors.c | 11 +- .../src/plugins/config/configrevowidget.cpp | 120 ++++++++++++------ .../src/plugins/config/configrevowidget.h | 19 +-- 3 files changed, 98 insertions(+), 52 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index c854aa37a..5807857a1 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -88,6 +88,7 @@ static float mag_bias[3] = {0,0,0}; static float mag_scale[3] = {0,0,0}; static float accel_bias[3] = {0,0,0}; static float accel_scale[3] = {0,0,0}; +static float gyro_bias[3] = {0,0,0}; static float R[3][3] = {{0}}; static int8_t rotate = 0; @@ -379,9 +380,9 @@ static void SensorsTask(void *parameters) // Apply bias correction to the gyros GyrosBiasData gyrosBias; GyrosBiasGet(&gyrosBias); - gyrosData.x += gyrosBias.x; - gyrosData.y += gyrosBias.y; - gyrosData.z += gyrosBias.z; + gyrosData.x += gyrosBias.x - gyro_bias[0]; + gyrosData.y += gyrosBias.y - gyro_bias[1]; + gyrosData.z += gyrosBias.z - gyro_bias[2]; } GyrosSet(&gyrosData); @@ -448,9 +449,13 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { accel_scale[0] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_X]; accel_scale[1] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Y]; accel_scale[2] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Z]; + gyro_bias[0] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; + gyro_bias[1] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Y]; + gyro_bias[2] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Z]; AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); + bias_correct_gyro = (attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE); // Indicates not to expend cycles on rotation if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 75e7b13dd..ca0bb8fd1 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -214,15 +215,10 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : autoLoadWidgets(); // Connect the signals - connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(launchAccelBiasCalibration())); + connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(doStartAccelGyroBiasCalibration())); connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibration())); connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement())); - - // Leave this timer permanently connected. The timer itself is started and stopped. - connect(&progressBarTimer, SIGNAL(timeout()), this, SLOT(incrementProgress())); - - // Connect the help button } ConfigRevoWidget::~ConfigRevoWidget() @@ -248,11 +244,10 @@ void ConfigRevoWidget::resizeEvent(QResizeEvent *event) m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); } - /** - Starts an accelerometer bias calibration. + * Starts an accelerometer bias calibration. */ -void ConfigRevoWidget::launchAccelBiasCalibration() +void ConfigRevoWidget::doStartAccelGyroBiasCalibration() { m_ui->accelBiasStart->setEnabled(false); m_ui->accelBiasProgress->setValue(0); @@ -264,47 +259,98 @@ void ConfigRevoWidget::launchAccelBiasCalibration() revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); + // Disable gyro bias correction while calibrating + AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; + attitudeSettings->setData(attitudeSettingsData); + attitudeSettings->updated(); + accel_accum_x.clear(); accel_accum_y.clear(); accel_accum_z.clear(); + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + + UAVObject::Metadata mdata; /* Need to get as many accel updates as possible */ Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); - UAVObject::Metadata mdata = initialAccelsMdata; + mdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Q_ASSERT(gyros); + initialGyrosMdata = gyros->getMetadata(); + mdata = initialGyrosMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + gyros->setMetadata(mdata); + // Now connect to the accels and mag updates, gather for 100 samples collectingData = true; - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelBiasData(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); + connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); } /** Updates the accel bias raw values */ -void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) +void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) { - Q_UNUSED(obj); + QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); - Accels * accels = Accels::GetInstance(getObjectManager()); - Q_ASSERT(accels); - Accels::DataFields accelsData = accels->getData(); + switch(obj->getObjID()) { + case Accels::OBJID: + { + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Accels::DataFields accelsData = accels->getData(); - // This is necessary to prevent a race condition on disconnect signal and another update - if (collectingData == true) { accel_accum_x.append(accelsData.x); accel_accum_y.append(accelsData.y); accel_accum_z.append(accelsData.z); + break; + } + case Gyros::OBJID: + { + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Q_ASSERT(gyros); + Gyros::DataFields gyrosData = gyros->getData(); + + gyro_accum_x.append(gyrosData.x); + gyro_accum_y.append(gyrosData.y); + gyro_accum_z.append(gyrosData.z); + break; + } + default: + Q_ASSERT(0); } - m_ui->accelBiasProgress->setValue(m_ui->accelBiasProgress->value()+1); + // Work out the progress based on whichever has less + double p1 = (double) accel_accum_x.size() / (double) NOISE_SAMPLES; + double p2 = (double) accel_accum_y.size() / (double) NOISE_SAMPLES; + m_ui->accelBiasProgress->setValue(((p1 < p2) ? p1 : p2) * 100); + + if(accel_accum_x.size() >= NOISE_SAMPLES && + gyro_accum_y.size() >= NOISE_SAMPLES && + collectingData == true) { - if(accel_accum_x.size() >= 100 && collectingData == true) { collectingData = false; - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelBiasData(UAVObject*))); + + Accels * accels = Accels::GetInstance(getObjectManager()); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); + disconnect(gyros,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); + m_ui->accelBiasStart->setEnabled(true); RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); @@ -312,34 +358,26 @@ void ConfigRevoWidget::doGetAccelBiasData(UAVObject *obj) RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE; + // Update the biases based on collected data revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] += listMean(accel_accum_x); revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] += listMean(accel_accum_y); revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += ( listMean(accel_accum_z) + GRAVITY ); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_X] = listMean(gyro_accum_x); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Y] = listMean(gyro_accum_y); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Z] = listMean(gyro_accum_z); revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); + AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; + attitudeSettings->setData(attitudeSettingsData); + attitudeSettings->updated(); + accels->setMetadata(initialAccelsMdata); - } -} - -/** - Increment progress bar for noise measurements (not really based on feedback) - */ -void ConfigRevoWidget::incrementProgress() -{ - m_ui->noiseMeasurementProgress->setValue(m_ui->noiseMeasurementProgress->value()+1); - if (m_ui->noiseMeasurementProgress->value() >= m_ui->noiseMeasurementProgress->maximum()) { - progressBarTimer.stop(); - - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - disconnect(revoCalibration, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(noiseMeasured())); - collectingData = false; - - QErrorMessage err(this); - err.showMessage("Noise measurement timed out. State undetermined. Please power cycle."); - err.exec(); + gyros->setMetadata(initialGyrosMdata); } } diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 6822eb2ce..ae5bcf830 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -55,6 +55,9 @@ private: void drawVariancesGraph(); void displayPlane(QString elementID); + //! Computes the scale and bias of the mag based on collected data + void computeScaleBias(); + Ui_RevoSensorsWidget *m_ui; QGraphicsSvgItem *paperplane; QGraphicsSvgItem *sensorsBargraph; @@ -70,8 +73,6 @@ private: QMutex sensorsUpdateLock; double maxBarHeight; int phaseCounter; - int progressBarIndex; - QTimer progressBarTimer; const static double maxVarValue; const static int calibrationDelay = 10; @@ -100,15 +101,17 @@ private: static const int NOISE_SAMPLES = 100; private slots: - void launchAccelBiasCalibration(); - void incrementProgress(); - + //! Overriden method from the configTaskWidget to update UI virtual void refreshWidgetsValues(UAVObject * obj=NULL); - void savePositionData(); - void computeScaleBias(); + + // Slots for calibrating the mags void doStartSixPointCalibration(); void doGetSixPointCalibrationMeasurement(UAVObject * obj); - void doGetAccelBiasData(UAVObject*); + void savePositionData(); + + // Slots for calibrating the accel and gyro + void doStartAccelGyroBiasCalibration(); + void doGetAccelGyroBiasData(UAVObject*); // Slots for measuring the sensor noise void doStartNoiseMeasurement(); From a91c21f53fb8454ac599fa74a9d2ebc4c6b8ad11 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 14 Jun 2012 09:57:46 -0500 Subject: [PATCH 095/508] Don't restore the accel metadata after six point calibration unless it was actually saved and changed --- .../src/plugins/config/configrevowidget.cpp | 36 ++++++++++++------- 1 file changed, 24 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index ca0bb8fd1..8863c5da8 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -415,19 +415,22 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) #endif collectingData = false; + m_ui->sixPointsSave->setEnabled(true); + +#ifdef SIX_POINT_CAL_ACCEL + // Store the mean for this position for the accel Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - - m_ui->sixPointsSave->setEnabled(true); -#ifdef SIX_POINT_CAL_ACCEL accel_data_x[position] = listMean(accel_accum_x); accel_data_y[position] = listMean(accel_accum_y); accel_data_z[position] = listMean(accel_accum_z); #endif + + // Store the mean for this position for the mag + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); mag_data_x[position] = listMean(mag_accum_x); mag_data_y[position] = listMean(mag_accum_y); mag_data_z[position] = listMean(mag_accum_z); @@ -459,7 +462,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) m_ui->sixPointsSave->setEnabled(false); /* Cleanup original settings */ +#ifdef SIX_POINT_CAL_ACCEL accels->setMetadata(initialAccelsMdata); +#endif mag->setMetadata(initialMagMdata); } } @@ -597,10 +602,14 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z return 1; } +/** + * Computes the scale and bias for the magnetomer and (compile option) + * for the accel once all the data has been collected in 6 positions. + */ void ConfigRevoWidget::computeScaleBias() { double S[3], b[3]; - double Be_lenght; + double Be_length; RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); @@ -621,8 +630,8 @@ void ConfigRevoWidget::computeScaleBias() #endif // Calibration mag - Be_lenght = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); - SixPointInConstFieldCal( Be_lenght, mag_data_x, mag_data_y, mag_data_z, S, b); + Be_length = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); + SixPointInConstFieldCal( Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); @@ -699,18 +708,21 @@ void ConfigRevoWidget::doStartSixPointCalibration() mag_accum_y.clear(); mag_accum_z.clear(); - /* Need to get as many accel and mag updates as possible */ +#ifdef SIX_POINT_CAL_ACCEL + /* Need to get as many accel updates as possible */ Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); initialAccelsMdata = accels->getMetadata(); UAVObject::Metadata mdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); +#endif + /* Need to get as many mag updates as possible */ + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); initialMagMdata = mag->getMetadata(); mdata = initialMagMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); From f1aad76f7157098abec82bf547ff5a23e2296839 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 14 Jun 2012 10:01:05 -0500 Subject: [PATCH 096/508] Reorder functions for six point calibration to make more sense (the order they are run) and add some comments --- .../src/plugins/config/configrevowidget.cpp | 439 +++++++++--------- 1 file changed, 226 insertions(+), 213 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 8863c5da8..41f7e8152 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -381,125 +381,7 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) } } -void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) -{ - QMutexLocker lock(&sensorsUpdateLock); - // This is necessary to prevent a race condition on disconnect signal and another update - if (collectingData == true) { - if( obj->getObjID() == Accels::OBJID ) { -#ifdef SIX_POINT_CAL_ACCEL - Accels * accels = Accels::GetInstance(getObjectManager()); - Q_ASSERT(accels); - Accels::DataFields accelsData = accels->getData(); - accel_accum_x.append(accelsData.x); - accel_accum_y.append(accelsData.y); - accel_accum_z.append(accelsData.z); -#endif - } else if( obj->getObjID() == Magnetometer::OBJID ) { - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); - Magnetometer::DataFields magData = mag->getData(); - mag_accum_x.append(magData.x); - mag_accum_y.append(magData.y); - mag_accum_z.append(magData.z); - } else { - Q_ASSERT(0); - } - } - -#ifdef SIX_POINT_CAL_ACCEL - if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { -#else - if(mag_accum_x.size() >= 20 && collectingData == true) { -#endif - collectingData = false; - - m_ui->sixPointsSave->setEnabled(true); - -#ifdef SIX_POINT_CAL_ACCEL - // Store the mean for this position for the accel - Accels * accels = Accels::GetInstance(getObjectManager()); - Q_ASSERT(accels); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - accel_data_x[position] = listMean(accel_accum_x); - accel_data_y[position] = listMean(accel_accum_y); - accel_data_z[position] = listMean(accel_accum_z); -#endif - - // Store the mean for this position for the mag - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); - disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - mag_data_x[position] = listMean(mag_accum_x); - mag_data_y[position] = listMean(mag_accum_y); - mag_data_z[position] = listMean(mag_accum_z); - - position = (position + 1) % 6; - if(position == 1) { - m_ui->sixPointCalibInstructions->append("Place with left side down and click save position..."); - displayPlane("plane-left"); - } - if(position == 2) { - m_ui->sixPointCalibInstructions->append("Place upside down and click save position..."); - displayPlane("plane-flip"); - } - if(position == 3) { - m_ui->sixPointCalibInstructions->append("Place with right side down and click save position..."); - displayPlane("plane-right"); - } - if(position == 4) { - m_ui->sixPointCalibInstructions->append("Place with nose up and click save position..."); - displayPlane("plane-up"); - } - if(position == 5) { - m_ui->sixPointCalibInstructions->append("Place with nose down and click save position..."); - displayPlane("plane-down"); - } - if(position == 0) { - computeScaleBias(); - m_ui->sixPointsStart->setEnabled(true); - m_ui->sixPointsSave->setEnabled(false); - - /* Cleanup original settings */ -#ifdef SIX_POINT_CAL_ACCEL - accels->setMetadata(initialAccelsMdata); -#endif - mag->setMetadata(initialMagMdata); - } - } -} - -/** - * Saves the data from the aircraft in one of six positions - */ -void ConfigRevoWidget::savePositionData() -{ - QMutexLocker lock(&sensorsUpdateLock); - m_ui->sixPointsSave->setEnabled(false); - - accel_accum_x.clear(); - accel_accum_y.clear(); - accel_accum_z.clear(); - mag_accum_x.clear(); - mag_accum_y.clear(); - mag_accum_z.clear(); - gyro_accum_x.clear(); - gyro_accum_y.clear(); - gyro_accum_z.clear(); - - collectingData = true; - - Accels * accels = Accels::GetInstance(getObjectManager()); - Q_ASSERT(accels); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); - - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - - m_ui->sixPointCalibInstructions->append("Hold..."); -} int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfSolution) { @@ -602,57 +484,13 @@ int SixPointInConstFieldCal( double ConstMag, double x[6], double y[6], double z return 1; } -/** - * Computes the scale and bias for the magnetomer and (compile option) - * for the accel once all the data has been collected in 6 positions. - */ -void ConfigRevoWidget::computeScaleBias() -{ - double S[3], b[3]; - double Be_length; - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - Q_ASSERT(homeLocation); - RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); - HomeLocation::DataFields homeLocationData = homeLocation->getData(); - -#ifdef SIX_POINT_CAL_ACCEL - // Calibration accel - SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; -#endif - - // Calibration mag - Be_length = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); - SixPointInConstFieldCal( Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; - - revoCalibration->setData(revoCalibrationData); - - position = -1; //set to run again -#ifdef SIX_POINT_CAL_ACCEL - m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); -#else - m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); -#endif - -} +/********** Functions for six point calibration **************/ /** - Six point calibration mode + * Called by the "Start" button. Sets up the meta data and enables the + * buttons to perform six point calibration of the magnetometer (optionally + * accel) to compute the scale and bias of this sensor based on the current + * home location magnetic strength. */ void ConfigRevoWidget::doStartSixPointCalibration() { @@ -738,7 +576,181 @@ void ConfigRevoWidget::doStartSixPointCalibration() position = 0; } +/** + * Saves the data from the aircraft in one of six positions. + * This is called when they click "save position" and starts + * averaging data for this position. + */ +void ConfigRevoWidget::savePositionData() +{ + QMutexLocker lock(&sensorsUpdateLock); + m_ui->sixPointsSave->setEnabled(false); + accel_accum_x.clear(); + accel_accum_y.clear(); + accel_accum_z.clear(); + mag_accum_x.clear(); + mag_accum_y.clear(); + mag_accum_z.clear(); + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + + collectingData = true; + + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + + connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + + m_ui->sixPointCalibInstructions->append("Hold..."); +} + +/** + * Grab a sample of mag (optionally accel) data while in this position and + * store it for averaging. When sufficient points are collected advance + * to the next position (give message to user) or compute the scale and bias + */ +void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) +{ + QMutexLocker lock(&sensorsUpdateLock); + + // This is necessary to prevent a race condition on disconnect signal and another update + if (collectingData == true) { + if( obj->getObjID() == Accels::OBJID ) { +#ifdef SIX_POINT_CAL_ACCEL + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + Accels::DataFields accelsData = accels->getData(); + accel_accum_x.append(accelsData.x); + accel_accum_y.append(accelsData.y); + accel_accum_z.append(accelsData.z); +#endif + } else if( obj->getObjID() == Magnetometer::OBJID ) { + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + Magnetometer::DataFields magData = mag->getData(); + mag_accum_x.append(magData.x); + mag_accum_y.append(magData.y); + mag_accum_z.append(magData.z); + } else { + Q_ASSERT(0); + } + } + +#ifdef SIX_POINT_CAL_ACCEL + if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { +#else + if(mag_accum_x.size() >= 20 && collectingData == true) { +#endif + collectingData = false; + + m_ui->sixPointsSave->setEnabled(true); + +#ifdef SIX_POINT_CAL_ACCEL + // Store the mean for this position for the accel + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); + disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + accel_data_x[position] = listMean(accel_accum_x); + accel_data_y[position] = listMean(accel_accum_y); + accel_data_z[position] = listMean(accel_accum_z); +#endif + + // Store the mean for this position for the mag + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + mag_data_x[position] = listMean(mag_accum_x); + mag_data_y[position] = listMean(mag_accum_y); + mag_data_z[position] = listMean(mag_accum_z); + + position = (position + 1) % 6; + if(position == 1) { + m_ui->sixPointCalibInstructions->append("Place with left side down and click save position..."); + displayPlane("plane-left"); + } + if(position == 2) { + m_ui->sixPointCalibInstructions->append("Place upside down and click save position..."); + displayPlane("plane-flip"); + } + if(position == 3) { + m_ui->sixPointCalibInstructions->append("Place with right side down and click save position..."); + displayPlane("plane-right"); + } + if(position == 4) { + m_ui->sixPointCalibInstructions->append("Place with nose up and click save position..."); + displayPlane("plane-up"); + } + if(position == 5) { + m_ui->sixPointCalibInstructions->append("Place with nose down and click save position..."); + displayPlane("plane-down"); + } + if(position == 0) { + computeScaleBias(); + m_ui->sixPointsStart->setEnabled(true); + m_ui->sixPointsSave->setEnabled(false); + + /* Cleanup original settings */ +#ifdef SIX_POINT_CAL_ACCEL + accels->setMetadata(initialAccelsMdata); +#endif + mag->setMetadata(initialMagMdata); + } + } +} + +/** + * Computes the scale and bias for the magnetomer and (compile option) + * for the accel once all the data has been collected in 6 positions. + */ +void ConfigRevoWidget::computeScaleBias() +{ + double S[3], b[3]; + double Be_length; + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + Q_ASSERT(homeLocation); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + +#ifdef SIX_POINT_CAL_ACCEL + // Calibration accel + SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; +#endif + + // Calibration mag + Be_length = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); + SixPointInConstFieldCal( Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; + + revoCalibration->setData(revoCalibrationData); + + position = -1; //set to run again +#ifdef SIX_POINT_CAL_ACCEL + m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); +#else + m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); +#endif + +} /** Rotate the paper plane @@ -751,52 +763,7 @@ void ConfigRevoWidget::displayPlane(QString elementID) } - -/** - Draws the sensor variances bargraph - */ -void ConfigRevoWidget::drawVariancesGraph() -{ - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - if(!revoCalibration) - return; - RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); - - // The expected range is from 1E-6 to 1E-1 - double steps = 6; // 6 bars on the graph - float accel_x_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_X])); - if(accel_x) - accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); - float accel_y_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Y])); - if(accel_y) - accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); - float accel_z_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Z])); - if(accel_z) - accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); - - float gyro_x_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_X])); - if(gyro_x) - gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); - float gyro_y_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Y])); - if(gyro_y) - gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); - float gyro_z_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Z])); - if(gyro_z) - gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); - - // Scale by 1e-3 because mag vars are much higher. - float mag_x_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_X])); - if(mag_x) - mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); - float mag_y_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Y])); - if(mag_y) - mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); - float mag_z_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Z])); - if(mag_z) - mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); -} - +/*********** Noise measurement functions **************/ /** * Connect sensor updates and timeout for measuring the noise */ @@ -937,6 +904,52 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) } } +/********** UI Functions *************/ +/** + Draws the sensor variances bargraph + */ +void ConfigRevoWidget::drawVariancesGraph() +{ + RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + if(!revoCalibration) + return; + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + + // The expected range is from 1E-6 to 1E-1 + double steps = 6; // 6 bars on the graph + float accel_x_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_X])); + if(accel_x) + accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); + float accel_y_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Y])); + if(accel_y) + accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); + float accel_z_var = -1/steps*(1+steps+log10(revoCalibrationData.accel_var[RevoCalibration::ACCEL_VAR_Z])); + if(accel_z) + accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); + + float gyro_x_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_X])); + if(gyro_x) + gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); + float gyro_y_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Y])); + if(gyro_y) + gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); + float gyro_z_var = -1/steps*(1+steps+log10(revoCalibrationData.gyro_var[RevoCalibration::GYRO_VAR_Z])); + if(gyro_z) + gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); + + // Scale by 1e-3 because mag vars are much higher. + float mag_x_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_X])); + if(mag_x) + mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); + float mag_y_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Y])); + if(mag_y) + mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); + float mag_z_var = -1/steps*(1+steps+log10(1e-3*revoCalibrationData.mag_var[RevoCalibration::MAG_VAR_Z])); + if(mag_z) + mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); +} + /** * Called by the ConfigTaskWidget parent when RevoCalibration is updated * to update the UI From 97483bddad64bcf5a6b801e3d1d7985743096e62 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 14 Jun 2012 10:07:45 -0500 Subject: [PATCH 097/508] Fix some indentation in the mag calibration code and no need to clear the gyro accumulator. --- .../src/plugins/config/configrevowidget.cpp | 63 +++++++++---------- 1 file changed, 30 insertions(+), 33 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 41f7e8152..48db4a3aa 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -537,43 +537,43 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibration->setData(revoCalibrationData); - Thread::usleep(100000); + Thread::usleep(100000); - gyro_accum_x.clear(); - gyro_accum_y.clear(); - gyro_accum_z.clear(); - mag_accum_x.clear(); - mag_accum_y.clear(); - mag_accum_z.clear(); + gyro_accum_x.clear(); + gyro_accum_y.clear(); + gyro_accum_z.clear(); + mag_accum_x.clear(); + mag_accum_y.clear(); + mag_accum_z.clear(); #ifdef SIX_POINT_CAL_ACCEL - /* Need to get as many accel updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); - Q_ASSERT(accels); + /* Need to get as many accel updates as possible */ + Accels * accels = Accels::GetInstance(getObjectManager()); + Q_ASSERT(accels); - initialAccelsMdata = accels->getMetadata(); - UAVObject::Metadata mdata = initialAccelsMdata; - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = 100; - accels->setMetadata(mdata); + initialAccelsMdata = accels->getMetadata(); + UAVObject::Metadata mdata = initialAccelsMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + accels->setMetadata(mdata); #endif - /* Need to get as many mag updates as possible */ - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); - Q_ASSERT(mag); - initialMagMdata = mag->getMetadata(); - mdata = initialMagMdata; - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = 100; - mag->setMetadata(mdata); + /* Need to get as many mag updates as possible */ + Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Q_ASSERT(mag); + initialMagMdata = mag->getMetadata(); + mdata = initialMagMdata; + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = 100; + mag->setMetadata(mdata); - /* Show instructions and enable controls */ - m_ui->sixPointCalibInstructions->clear(); - m_ui->sixPointCalibInstructions->append("Place horizontally and click save position..."); - displayPlane("plane-horizontal"); - m_ui->sixPointsStart->setEnabled(false); - m_ui->sixPointsSave->setEnabled(true); - position = 0; + /* Show instructions and enable controls */ + m_ui->sixPointCalibInstructions->clear(); + m_ui->sixPointCalibInstructions->append("Place horizontally and click save position..."); + displayPlane("plane-horizontal"); + m_ui->sixPointsStart->setEnabled(false); + m_ui->sixPointsSave->setEnabled(true); + position = 0; } /** @@ -592,9 +592,6 @@ void ConfigRevoWidget::savePositionData() mag_accum_x.clear(); mag_accum_y.clear(); mag_accum_z.clear(); - gyro_accum_x.clear(); - gyro_accum_y.clear(); - gyro_accum_z.clear(); collectingData = true; From 1ac807e1e0e10a1f701edba3f311692adda17437 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 13:15:21 -0500 Subject: [PATCH 098/508] Fix small bugt in the revo calibration --- ground/openpilotgcs/src/plugins/config/configrevowidget.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 48db4a3aa..5364fbb44 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -546,13 +546,15 @@ void ConfigRevoWidget::doStartSixPointCalibration() mag_accum_y.clear(); mag_accum_z.clear(); + UAVObject::Metadata mdata; + #ifdef SIX_POINT_CAL_ACCEL /* Need to get as many accel updates as possible */ Accels * accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); - UAVObject::Metadata mdata = initialAccelsMdata; + mdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); From 62436270e3d189b47ce7626c9ad64f33e7081b39 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 13:15:45 -0500 Subject: [PATCH 099/508] When moving waypoints on the map, keep the previous altitude --- ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 1bc82c5d7..eb5892281 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -188,7 +188,8 @@ void PathCompiler::doUpdateWaypoints(PathCompiler::waypoint changedWaypoint, int Waypoint::DataFields oldWaypointUAVO = waypointInst->getData(); oldWaypointUAVO.Position[0] = changedWaypointUAVO.Position[0]; oldWaypointUAVO.Position[1] = changedWaypointUAVO.Position[1]; - oldWaypointUAVO.Position[2] = changedWaypointUAVO.Position[2]; + // Don't take the altitude from the map for now + waypointInst->setData(oldWaypointUAVO); waypointInst->updated(); } From 5b2f4d6d91fd9defadc427b098d9acb42e0cbdb8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 14:56:55 -0500 Subject: [PATCH 100/508] Remove an outdated connect in waypointeditor --- .../openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp index e0f59c60f..d89af2b30 100644 --- a/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp +++ b/ground/openpilotgcs/src/plugins/waypointeditor/waypointtable.cpp @@ -57,9 +57,6 @@ WaypointTable::WaypointTable(QObject *parent) : connect(waypoint, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(waypointsUpdated(UAVObject*))); } - connect(waypointObj, SIGNAL(), - this, SLOT(waypointsUpdated(UAVObject*))); - headers.clear(); headers.append(QString("North")); headers.append(QString("East")); From be360d3c21fd17f376bb642d279fda2d69072bf7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 15:51:12 -0500 Subject: [PATCH 101/508] Fix waypoint visualization in OPMap to work for multiple maps --- ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 ++ ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp | 4 ---- ground/openpilotgcs/src/plugins/opmap/pathcompiler.h | 1 + 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 52ab71ae9..568f5c5b8 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2541,12 +2541,14 @@ void OPMapGadgetWidget::doVisualizationChanged(QList way WayPointItem * wayPointItem = m_map->WPCreate(position, 0, QString(index)); Q_ASSERT(wayPointItem); if(wayPointItem) { + wayPointItem->SetNumber(index); wayPointItem->setFlag(QGraphicsItem::ItemIsMovable, true); wayPointItem->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); index++; } connect(wayPointItem, SIGNAL(WPDropped(WayPointItem*)), this, SLOT(WPDropped(WayPointItem*))); } + } /** diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index eb5892281..59ac2e200 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -213,7 +213,6 @@ void PathCompiler::doDelWaypoint(int index) int numWaypoints = objManager->getNumInstances(waypoint->getObjID()); for (int i = index; i < numWaypoints - 1; i++) { - qDebug() << "Copying from" << i+1 << "to" << i; Waypoint *waypointDest = Waypoint::GetInstance(objManager, i); Q_ASSERT(waypointDest); @@ -232,7 +231,6 @@ void PathCompiler::doDelWaypoint(int index) // Set the second to last waypoint to stop (and last for safety) // the functional equivalent to deleting for (int i = numWaypoints - 2; i < numWaypoints; i++) { - qDebug() << "Stopping" << i; waypoint = Waypoint::GetInstance(objManager, i); Q_ASSERT(waypoint); if (waypoint) { @@ -274,8 +272,6 @@ void PathCompiler::doDelAllWaypoints() */ void PathCompiler::doUpdateFromUAV(UAVObject *obj) { - static QList previousWaypoints; - UAVObjectManager *objManager = getObjectManager(); if (!objManager) return; diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index f3bdc95c4..2fb615195 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -88,6 +88,7 @@ private: //! Convert a UAVO waypoint to the local structure Waypoint::DataFields InternalToUavo(waypoint); + QList previousWaypoints; signals: /** * Indicates something changed the waypoints and the map should From 495bb280c7c158a4bd3646b5a4766c3d2048fe25 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 15:51:40 -0500 Subject: [PATCH 102/508] Suppress long standing error message from telemetry we've had for ages. It probably should be fixed properly though. --- ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index c1463013a..ef43f1e5f 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -367,10 +367,10 @@ void Telemetry::processObjectQueue() { // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); - // Don nothing if a transaction is already in progress (should not happen) + // Do nothing if a transaction is already in progress (should not happen) + // but it does a lot if (transPending) { - qxtLog->error("Telemetry: Dequeue while a transaction pending!"); return; } From 416618a26f37133aea2f876f3953d6d4a208d9e9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 16:01:15 -0500 Subject: [PATCH 103/508] Show the altitude on the map --- ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp | 3 ++- ground/openpilotgcs/src/plugins/opmap/pathcompiler.h | 1 + 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 568f5c5b8..ebb489a13 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2538,7 +2538,7 @@ void OPMapGadgetWidget::doVisualizationChanged(QList way foreach (PathCompiler::waypoint waypoint, waypoints) { internals::PointLatLng position(waypoint.latitude, waypoint.longitude); - WayPointItem * wayPointItem = m_map->WPCreate(position, 0, QString(index)); + WayPointItem * wayPointItem = m_map->WPCreate(position, waypoint.altitude, QString(index)); Q_ASSERT(wayPointItem); if(wayPointItem) { wayPointItem->SetNumber(index); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp index 59ac2e200..a7c9425a9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.cpp @@ -335,6 +335,7 @@ struct PathCompiler::waypoint PathCompiler::UavoToInternal(Waypoint::DataFields internalWaypoint.latitude = LLA[0]; internalWaypoint.longitude = LLA[1]; + internalWaypoint.altitude = LLA[2]; return internalWaypoint; } @@ -363,7 +364,7 @@ Waypoint::DataFields PathCompiler::InternalToUavo(waypoint internal) // TODO: Give the point a concept of altitude LLA[0] = internal.latitude; LLA[1] = internal.longitude; - LLA[2] = -50; + LLA[2] = internal.altitude; Utils::CoordinateConversions().GetNED(homeLLA, LLA, NED); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h index 2fb615195..ed721794c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathcompiler.h @@ -76,6 +76,7 @@ public: double latitude; double longitude; + double altitude; }; private: From f8d196ffe8149ab7291684fd7d807f2fc3040d90 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 19:43:34 -0500 Subject: [PATCH 104/508] Added support for board voltage monitor to battery module. The module can be configured to enable what's needed from board voltage, battery voltage and battery current measurement. In GCS the POWER box in system healt will show alarm related to the supply voltage to the board. If a power warning/critical alarm is raised, the warning condition is left even if the board voltage return to an acceptable value. Conflicts: ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg shared/uavobjectdefinition/systemalarms.xml --- flight/Modules/Battery/battery.c | 127 +- flight/PiOS/Boards/STM32F4xx_Revolution.h | 4 +- .../diagrams/default/system-health.svg | 7221 ++++++++--------- .../flightbatterysettings.xml | 6 +- .../flightbatterystate.xml | 1 + shared/uavobjectdefinition/systemalarms.xml | 2 +- 6 files changed, 3555 insertions(+), 3806 deletions(-) diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index 1f9a7e720..13fc9f29b 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -55,7 +55,9 @@ // Configuration // #define SAMPLE_PERIOD_MS 500 - +#define BATTERY_BOARD_VOLTAGE_WARNING 4.5 +#define BATTERY_BOARD_VOLTAGE_CRITICAL 3.5 +#define BATTERY_BOARD_VOLTAGE_ERROR 1.0 // Private types // Private variables @@ -98,53 +100,122 @@ int32_t BatteryInitialize(void) } MODULE_INITCALL(BatteryInitialize, 0) - +#define HAS_SENSOR(x) batterySettings.SensorType[x]==FLIGHTBATTERYSETTINGS_SENSORTYPE_ENABLED static void onTimer(UAVObjEvent* ev) { static FlightBatteryStateData flightBatteryData; - + static bool BoardPowerWarning= false; FlightBatterySettingsData batterySettings; - static float dT = SAMPLE_PERIOD_MS / 1000.0; - float energyRemaining; FlightBatterySettingsGet(&batterySettings); + static float dT = SAMPLE_PERIOD_MS / 1000.0; + float energyRemaining; + + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BOARDVOLTAGE) ) + flightBatteryData.BoardSupplyVoltage=((float)PIOS_ADC_PinGet(4)) * PIOS_ADC_VOLTAGE_SCALE * 6.1; + else + flightBatteryData.BoardSupplyVoltage = -1; + //calculate the battery parameters - flightBatteryData.Voltage = ((float)PIOS_ADC_PinGet(0)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_VOLTAGEFACTOR]; //in Volts - flightBatteryData.Current = ((float)PIOS_ADC_PinGet(1)) * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_CURRENTFACTOR]; //in Amps + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYVOLTAGE) ) + flightBatteryData.Voltage = ((float)PIOS_ADC_PinGet(0)) * PIOS_ADC_VOLTAGE_SCALE * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_VOLTAGEFACTOR]; //in Volts + else + flightBatteryData.Voltage = -1; - flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * 1000.0f * dT / 3600.0f) ;//in mAh - if (flightBatteryData.Current > flightBatteryData.PeakCurrent)flightBatteryData.PeakCurrent = flightBatteryData.Current; //in Amps - flightBatteryData.AvgCurrent=(flightBatteryData.AvgCurrent*0.8)+(flightBatteryData.Current*0.2); //in Amps + + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYCURRENT)) + { + flightBatteryData.Current = ((float)PIOS_ADC_PinGet(1)) * PIOS_ADC_VOLTAGE_SCALE * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_CURRENTFACTOR]; //in Amps + flightBatteryData.ConsumedEnergy += (flightBatteryData.Current * 1000.0f * dT / 3600.0f) ;//in mAh + + if (flightBatteryData.Current > flightBatteryData.PeakCurrent) + flightBatteryData.PeakCurrent = flightBatteryData.Current; //in Amps + + flightBatteryData.AvgCurrent=(flightBatteryData.AvgCurrent*0.8)+(flightBatteryData.Current*0.2); //in Amps - //sanity checks - if (flightBatteryData.AvgCurrent<0)flightBatteryData.AvgCurrent=0.0; - if (flightBatteryData.PeakCurrent<0)flightBatteryData.PeakCurrent=0.0; - if (flightBatteryData.ConsumedEnergy<0)flightBatteryData.ConsumedEnergy=0.0; + //sanity checks + if (flightBatteryData.AvgCurrent<0) + flightBatteryData.AvgCurrent=0.0; + if (flightBatteryData.PeakCurrent<0) + flightBatteryData.PeakCurrent=0.0; + if (flightBatteryData.ConsumedEnergy<0) + flightBatteryData.ConsumedEnergy=0.0; - energyRemaining = batterySettings.Capacity - flightBatteryData.ConsumedEnergy; // in mAh - flightBatteryData.EstimatedFlightTime = ((energyRemaining / (flightBatteryData.AvgCurrent*1000.0))*3600.0);//in Sec + energyRemaining = batterySettings.Capacity - flightBatteryData.ConsumedEnergy; // in mAh + flightBatteryData.EstimatedFlightTime = ((energyRemaining / (flightBatteryData.AvgCurrent*1000.0))*3600.0);//in Sec + } + else + if(flightBatteryData.Current != -1) + { + flightBatteryData.Current = -1; + flightBatteryData.EstimatedFlightTime = 0; + flightBatteryData.AvgCurrent = 0; + flightBatteryData.ConsumedEnergy = 0; + } - //generate alarms where needed... - if ((flightBatteryData.Voltage<=0)&&(flightBatteryData.Current<=0)) + //Check for battery inputs disconnection (don't think this really works. Do we need pull down on inputs?). + if (flightBatteryData.Voltage == 0 || + flightBatteryData.Current == 0 ) { AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_ERROR); AlarmsSet(SYSTEMALARMS_ALARM_FLIGHTTIME, SYSTEMALARMS_ALARM_ERROR); } else { - if (flightBatteryData.EstimatedFlightTime < 30) AlarmsSet(SYSTEMALARMS_ALARM_FLIGHTTIME, SYSTEMALARMS_ALARM_CRITICAL); - else if (flightBatteryData.EstimatedFlightTime < 60) AlarmsSet(SYSTEMALARMS_ALARM_FLIGHTTIME, SYSTEMALARMS_ALARM_WARNING); - else AlarmsClear(SYSTEMALARMS_ALARM_FLIGHTTIME); - + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYCURRENT)) + { + if (flightBatteryData.EstimatedFlightTime < 30) + AlarmsSet(SYSTEMALARMS_ALARM_FLIGHTTIME, SYSTEMALARMS_ALARM_CRITICAL); + else + if (flightBatteryData.EstimatedFlightTime < 60) + AlarmsSet(SYSTEMALARMS_ALARM_FLIGHTTIME, SYSTEMALARMS_ALARM_WARNING); + else + AlarmsClear(SYSTEMALARMS_ALARM_FLIGHTTIME); + } + // FIXME: should make the battery voltage detection dependent on battery type. - if (flightBatteryData.Voltage < batterySettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_ALARM]) - AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_CRITICAL); - else if (flightBatteryData.Voltage < batterySettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_WARNING]) - AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING); - else AlarmsClear(SYSTEMALARMS_ALARM_BATTERY); + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYVOLTAGE)){ + if (flightBatteryData.Voltage < batterySettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_ALARM] ) + AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_CRITICAL); + else + if (flightBatteryData.Voltage < batterySettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_WARNING]) + AlarmsSet(SYSTEMALARMS_ALARM_BATTERY, SYSTEMALARMS_ALARM_WARNING); + else + AlarmsClear(SYSTEMALARMS_ALARM_BATTERY); + } } - + + if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BOARDVOLTAGE) ) + { + // power ia disconnected from the board (it is powered by usb) + if(flightBatteryData.BoardSupplyVoltage!= -1 && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_ERROR) + { + AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_ERROR); + BoardPowerWarning=false; + } + else + { + if(flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_CRITICAL) + { + AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_CRITICAL); + BoardPowerWarning=true; + } + else if (flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_WARNING) + { + AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); + BoardPowerWarning=true; + } + else + { + // if there was any previous warning/critical condition, notify the problem leaving the warning + if(BoardPowerWarning) + AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); + else + AlarmsClear(SYSTEMALARMS_ALARM_POWER); + } + } + } FlightBatteryStateSet(&flightBatteryData); } diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 7ede8f47d..370abd2e3 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -244,7 +244,8 @@ extern uint32_t pios_com_vcp_id; {GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ - {NULL, 0, ADC_Channel_TempSensor} /* Temperature sensor */ \ + {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ + {GPIOC, GPIO_Pin_2, ADC_Channel_12} \ } /* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ @@ -253,6 +254,7 @@ extern uint32_t pios_com_vcp_id; #define PIOS_ADC_NUM_CHANNELS 4 #define PIOS_ADC_MAX_OVERSAMPLING 2 #define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_VOLTAGE_SCALE 3.30/4096.0 //------------------------- // USB diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 1d19aaf5b..2d76c9359 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -1,5 +1,5 @@ - + image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Boot Fault - -Sensors - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Boot Fault + Battery + + diff --git a/shared/uavobjectdefinition/flightbatterysettings.xml b/shared/uavobjectdefinition/flightbatterysettings.xml index c95e7e817..874fada83 100644 --- a/shared/uavobjectdefinition/flightbatterysettings.xml +++ b/shared/uavobjectdefinition/flightbatterysettings.xml @@ -7,9 +7,9 @@ - - - + + + diff --git a/shared/uavobjectdefinition/flightbatterystate.xml b/shared/uavobjectdefinition/flightbatterystate.xml index 5cefbdd86..93f7fad1a 100644 --- a/shared/uavobjectdefinition/flightbatterystate.xml +++ b/shared/uavobjectdefinition/flightbatterystate.xml @@ -3,6 +3,7 @@ Battery status information. + diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index 91a3212ad..c25fa7029 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -2,7 +2,7 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + elementnames="OutOfMemory,StackOverflow,CPUOverload,EventSystem,Telemetry,ManualControl,Actuator,Attitude,Sensors,Stabilization,Guidance,Battery,FlightTime,I2C,GPS,BootFault,Power" defaultvalue="Uninitialised"/> From 9aa088fb9862dc6451d4106661bfc5d914bf22b6 Mon Sep 17 00:00:00 2001 From: a*morale Date: Sat, 16 Jun 2012 02:19:17 +0200 Subject: [PATCH 105/508] battery module: prevent the initial ramp up of the power supply to be identified as a low voltage condition --- flight/Modules/Battery/battery.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index 13fc9f29b..1479d7699 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -105,6 +105,8 @@ static void onTimer(UAVObjEvent* ev) { static FlightBatteryStateData flightBatteryData; static bool BoardPowerWarning= false; + // prevent that the initial ramp up of the power supply rail is identified as a power failure. + static bool BoardPowerOk = false; FlightBatterySettingsData batterySettings; FlightBatterySettingsGet(&batterySettings); @@ -193,15 +195,16 @@ static void onTimer(UAVObjEvent* ev) { AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_ERROR); BoardPowerWarning=false; + BoardPowerOk = false; } else { - if(flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_CRITICAL) + if(BoardPowerOk && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_CRITICAL) { AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_CRITICAL); BoardPowerWarning=true; } - else if (flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_WARNING) + else if (BoardPowerOk && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_WARNING) { AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); BoardPowerWarning=true; @@ -213,6 +216,7 @@ static void onTimer(UAVObjEvent* ev) AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); else AlarmsClear(SYSTEMALARMS_ALARM_POWER); + BoardPowerOk |= flightBatteryData.BoardSupplyVoltage > BATTERY_BOARD_VOLTAGE_WARNING; } } } From 62a60392e0f73a778aa3f8a5b76810069c65544f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 15 Jun 2012 19:51:57 -0500 Subject: [PATCH 106/508] Fix system health to show sensors again --- .../diagrams/default/system-health.svg | 137 +++++++----------- 1 file changed, 50 insertions(+), 87 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 2d76c9359..a0f35a6be 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -28,13 +28,13 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="9.3551549" - inkscape:cx="19.927168" - inkscape:cy="55.08885" - inkscape:current-layer="foreground" + inkscape:cx="50.081478" + inkscape:cy="34.009214" + inkscape:current-layer="background" id="namedview3608" showgrid="false" inkscape:window-width="1920" - inkscape:window-height="1152" + inkscape:window-height="1178" inkscape:window-x="0" inkscape:window-y="0" inkscape:window-maximized="1" @@ -732,11 +732,12 @@ y="355.57822" /> + y="345.96741" + inkscape:label="#Sensors" /> - - - - - - @@ -3154,29 +3127,6 @@ style="font-size:2.68472195px;fill:#ffffff" d="m 55.197106,55.45276 0,0.886168 -0.241206,0 0,-0.878302 c -10e-7,-0.138955 -0.02709,-0.242953 -0.08128,-0.311994 -0.05418,-0.06904 -0.13546,-0.10356 -0.243827,-0.103561 -0.130217,10e-7 -0.232904,0.04151 -0.308061,0.124535 -0.07516,0.08302 -0.112738,0.196199 -0.112738,0.339523 l 0,0.829799 -0.242516,0 0,-1.468207 0.242516,0 0,0.228096 c 0.05768,-0.08826 0.125409,-0.154247 0.20319,-0.197945 0.07865,-0.0437 0.169105,-0.06554 0.271356,-0.06555 0.168668,1e-6 0.296262,0.05244 0.382783,0.157308 0.08652,0.103999 0.129777,0.257374 0.129779,0.460125" /> - - - - - - - @@ -3357,6 +3307,19 @@ x="5.6416268" y="16.60899" style="font-size:4px;font-style:normal;font-variant:normal;font-weight:normal;font-stretch:normal;text-align:start;line-height:125%;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;fill-opacity:1;font-family:Bitstream Vera Sans;-inkscape-font-specification:Bitstream Vera Sans">Battery + Sensors Date: Fri, 15 Jun 2012 20:05:59 -0500 Subject: [PATCH 107/508] Remove uSD from graphics now it's removed from alarms --- .../diagrams/default/system-health.svg | 89 ++----------------- 1 file changed, 9 insertions(+), 80 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index a0f35a6be..616e681af 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -28,7 +28,7 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="9.3551549" - inkscape:cx="50.081478" + inkscape:cx="37.147432" inkscape:cy="34.009214" inkscape:current-layer="background" id="namedview3608" @@ -706,14 +706,6 @@ height="56.637238" x="576.71594" y="365.44907" /> - + inkscape:groupmode="layer" /> + inkscape:groupmode="layer" /> + inkscape:groupmode="layer" /> + inkscape:groupmode="layer" /> - - - - - Date: Fri, 15 Jun 2012 20:11:50 -0500 Subject: [PATCH 108/508] Add other states for bootfault such as Ok. --- .../diagrams/default/system-health.svg | 54 ++++++++++++++++--- 1 file changed, 48 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 616e681af..2ec58bd37 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -28,9 +28,9 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="9.3551549" - inkscape:cx="37.147432" - inkscape:cy="34.009214" - inkscape:current-layer="background" + inkscape:cx="42.866204" + inkscape:cy="35.940147" + inkscape:current-layer="g4794" id="namedview3608" showgrid="false" inkscape:window-width="1920" @@ -1862,18 +1862,60 @@ + + + Date: Tue, 26 Jun 2012 11:57:11 +0300 Subject: [PATCH 109/508] Make pathdesired update on change with throttling to avoid slamming telemetry in position hold mode. --- shared/uavobjectdefinition/pathdesired.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/pathdesired.xml b/shared/uavobjectdefinition/pathdesired.xml index 788efbcf5..fc47b8842 100644 --- a/shared/uavobjectdefinition/pathdesired.xml +++ b/shared/uavobjectdefinition/pathdesired.xml @@ -13,7 +13,7 @@ - + From 33beafed279b829a77fdcc1ba0ae917b4f8c967e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 3 Jul 2012 10:53:10 +0200 Subject: [PATCH 110/508] Remove outdated alarm for sdcard in systemmod. Only affected simulation. --- flight/Modules/System/systemmod.c | 9 --------- 1 file changed, 9 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..9f612cfcd 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -458,15 +458,6 @@ static void updateSystemAlarms() AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW); } -#if defined(PIOS_INCLUDE_SDCARD) - // Check for SD card - if (PIOS_SDCARD_IsMounted() == 0) { - AlarmsSet(SYSTEMALARMS_ALARM_SDCARD, SYSTEMALARMS_ALARM_ERROR); - } else { - AlarmsClear(SYSTEMALARMS_ALARM_SDCARD); - } -#endif - // Check for event errors UAVObjGetStats(&objStats); EventGetStats(&evStats); From 8d4e2214125d2204052a19d0fa957b904de4c7a7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 23 May 2012 00:15:28 -0500 Subject: [PATCH 111/508] Remove the disable IRQ commands in PIOS_COM since they aren't needed. --- flight/PiOS/Common/pios_com.c | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/flight/PiOS/Common/pios_com.c b/flight/PiOS/Common/pios_com.c index 20e32ffd3..ba54c1e61 100644 --- a/flight/PiOS/Common/pios_com.c +++ b/flight/PiOS/Common/pios_com.c @@ -197,9 +197,7 @@ static uint16_t PIOS_COM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t PIOS_Assert(valid); PIOS_Assert(com_dev->has_rx); - PIOS_IRQ_Disable(); uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->rx, buf, buf_len); - PIOS_IRQ_Enable(); if (bytes_into_fifo > 0) { /* Data has been added to the buffer */ @@ -223,9 +221,7 @@ static uint16_t PIOS_COM_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t PIOS_Assert(buf_len); PIOS_Assert(com_dev->has_tx); - PIOS_IRQ_Disable(); uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->tx, buf, buf_len); - PIOS_IRQ_Enable(); if (bytes_from_fifo > 0) { /* More space has been made in the buffer */ @@ -289,9 +285,7 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u return -2; } - PIOS_IRQ_Disable(); uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->tx, buffer, len); - PIOS_IRQ_Enable(); if (bytes_into_fifo > 0) { /* More data has been put in the tx buffer, make sure the tx is started */ @@ -469,6 +463,7 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len { PIOS_Assert(buf); PIOS_Assert(buf_len); + uint16_t bytes_from_fifo; struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id; @@ -479,9 +474,7 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len PIOS_Assert(com_dev->has_rx); check_again: - PIOS_IRQ_Disable(); - uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->rx, buf, buf_len); - PIOS_IRQ_Enable(); + bytes_from_fifo = fifoBuf_getData(&com_dev->rx, buf, buf_len); if (bytes_from_fifo == 0) { /* No more bytes in receive buffer */ From 6e12054a08b57abe0b5afabf105f2894175c6897 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 13 Jul 2012 18:17:52 -0500 Subject: [PATCH 112/508] Update the overo revision --- overo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/overo b/overo index 335a3486d..f9d96100b 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 335a3486dd41e48345209d0a65d49a8cc8b442a1 +Subproject commit f9d96100b5c5427eecc4b7ab9f6786f502ae5e14 From 9eee4f1bc7fae0042cac08757db008611a9b9642 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 Jul 2012 09:07:22 -0500 Subject: [PATCH 113/508] Made OverSynce an optional module. Conflicts: shared/uavobjectdefinition/hwsettings.xml --- flight/Modules/OveroSync/overosync.c | 24 +++++++++++++++++++++++ shared/uavobjectdefinition/hwsettings.xml | 2 +- 2 files changed, 25 insertions(+), 1 deletion(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index ed6bdaad9..7ca362dd5 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -31,6 +31,7 @@ */ #include "openpilot.h" +#include "hwsettings.h" #include "overosync.h" #include "overosyncstats.h" #include "systemstats.h" @@ -49,6 +50,7 @@ static UAVTalkConnection uavTalkCon; static xTaskHandle overoSyncTaskHandle; volatile bool buffer_swap_failed; volatile uint32_t buffer_swap_timeval; +static bool overoEnabled; // Private functions static void overoSyncTask(void *parameters); @@ -140,6 +142,23 @@ int32_t OveroSyncInitialize(void) { if(pios_spi_overo_id == 0) return -1; + +#ifdef MODULE_OVERO_BUILTIN + overoEnabled = true; +#else + + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + overoEnabled = true; + } else { + overoEnabled = false; + return -1; + } +#endif + OveroSyncStatsInitialize(); @@ -160,6 +179,11 @@ int32_t OveroSyncInitialize(void) */ int32_t OveroSyncStart(void) { + //Check if module is enabled or not + if (overoEnabled == false) { + return -1; + } + if(pios_spi_overo_id == 0) return -1; diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index cdb21f6c8..6113ff818 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -18,7 +18,7 @@ - + From 5f337afb36ed51250811e6f9a7a94a8b873986c4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 Jul 2012 09:21:38 -0500 Subject: [PATCH 114/508] Add a setting to determine when the overo module logs --- flight/Revolution/UAVObjects.inc | 1 + .../openpilotgcs/src/plugins/uavobjects/uavobjects.pro | 2 ++ shared/uavobjectdefinition/overosyncsettings.xml | 10 ++++++++++ 3 files changed, 13 insertions(+) create mode 100644 shared/uavobjectdefinition/overosyncsettings.xml diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index b93982078..29c617298 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -63,6 +63,7 @@ UAVOBJSRCFILENAMES += nedaccel UAVOBJSRCFILENAMES += nedposition UAVOBJSRCFILENAMES += objectpersistence UAVOBJSRCFILENAMES += overosyncstats +UAVOBJSRCFILENAMES += overosyncsettings UAVOBJSRCFILENAMES += pathplannersettings UAVOBJSRCFILENAMES += pathdesired UAVOBJSRCFILENAMES += positionactual diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 4a7451c9f..639fd2651 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -46,6 +46,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/systemalarms.h \ $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ $$UAVOBJECT_SYNTHETICS/overosyncstats.h \ + $$UAVOBJECT_SYNTHETICS/overosyncsettings.h \ $$UAVOBJECT_SYNTHETICS/systemsettings.h \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \ @@ -114,6 +115,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/systemalarms.cpp \ $$UAVOBJECT_SYNTHETICS/objectpersistence.cpp \ $$UAVOBJECT_SYNTHETICS/overosyncstats.cpp \ + $$UAVOBJECT_SYNTHETICS/overosyncsettings.cpp \ $$UAVOBJECT_SYNTHETICS/systemsettings.cpp \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \ diff --git a/shared/uavobjectdefinition/overosyncsettings.xml b/shared/uavobjectdefinition/overosyncsettings.xml new file mode 100644 index 000000000..4bfbfb5f8 --- /dev/null +++ b/shared/uavobjectdefinition/overosyncsettings.xml @@ -0,0 +1,10 @@ + + + Settings to control the behavior of the overo sync module + + + + + + + From 7bddf2a9886cd0eb81b88f00037fbbc2cf1868d3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 Jul 2012 17:38:49 -0500 Subject: [PATCH 115/508] Correct default value for overo sync settings --- overo | 2 +- shared/uavobjectdefinition/overosyncsettings.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/overo b/overo index f9d96100b..0919f3c8c 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit f9d96100b5c5427eecc4b7ab9f6786f502ae5e14 +Subproject commit 0919f3c8ce8469445ed6edaaa079cc92cca2fd97 diff --git a/shared/uavobjectdefinition/overosyncsettings.xml b/shared/uavobjectdefinition/overosyncsettings.xml index 4bfbfb5f8..b8b4bccbb 100644 --- a/shared/uavobjectdefinition/overosyncsettings.xml +++ b/shared/uavobjectdefinition/overosyncsettings.xml @@ -1,7 +1,7 @@ Settings to control the behavior of the overo sync module - + From b7af3c9584f9004e216dd860836af82e89ba82d4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 11:26:00 -0500 Subject: [PATCH 116/508] Bump the overo version --- overo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/overo b/overo index 0919f3c8c..207effa5b 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 0919f3c8ce8469445ed6edaaa079cc92cca2fd97 +Subproject commit 207effa5bdc993b280fa0c5c05aafc10fcfafa28 From bc075c5d2c15fd774939d74ef99daec770a89c5e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 11:45:45 -0500 Subject: [PATCH 117/508] Only schedule overo packets on the NSS line rising to avoid the frame sync errors we were seeing previously --- flight/Modules/OveroSync/overosync.c | 6 +++--- shared/uavobjectdefinition/overosyncstats.xml | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 7ca362dd5..c1b3968e8 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -58,7 +58,6 @@ static int32_t packData(uint8_t * data, int32_t length); static int32_t transmitData(); static void transmitDataDone(bool crc_ok, uint8_t crc_val); static void registerObject(UAVObjHandle obj); - // External variables extern int32_t pios_spi_overo_id; @@ -277,6 +276,7 @@ static void overoSyncTask(void *parameters) syncStats.Received = 0; syncStats.Connected = syncStats.Send > 500 ? OVEROSYNCSTATS_CONNECTED_TRUE : OVEROSYNCSTATS_CONNECTED_FALSE; syncStats.DroppedUpdates = overosync->failed_objects; + syncStats.FramesyncErrors = overosync->framesync_error; OveroSyncStatsSet(&syncStats); overosync->failed_objects = 0; overosync->sent_bytes = 0; @@ -342,7 +342,7 @@ static int32_t packData(uint8_t * data, int32_t length) xSemaphoreGive(overosync->buffer_lock); - // When the NSS line rises while we are packing data then a transaction doesn't start +/* // When the NSS line rises while we are packing data then a transaction doesn't start // because that means we will be here very shortly afterwards (priority of task making that // not always perfectly true) schedule the transaction here. if (buffer_swap_failed && (PIOS_DELAY_DiffuS(buffer_swap_timeval) < 50)) { @@ -352,7 +352,7 @@ static int32_t packData(uint8_t * data, int32_t length) buffer_swap_failed = false; too_long++; } - +*/ return length; } diff --git a/shared/uavobjectdefinition/overosyncstats.xml b/shared/uavobjectdefinition/overosyncstats.xml index a98ef3564..ec294f7db 100644 --- a/shared/uavobjectdefinition/overosyncstats.xml +++ b/shared/uavobjectdefinition/overosyncstats.xml @@ -4,6 +4,7 @@ + From 92a0311b32517dded0c5cf1d18752c7008a5fde1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 13:31:00 -0500 Subject: [PATCH 118/508] New pios_overo driver that handles the SPI communications to the overo --- flight/PiOS/STM32F4xx/pios_overo.c | 456 +++++++++++++++++++++++++++++ flight/PiOS/inc/pios_overo.h | 69 +++++ 2 files changed, 525 insertions(+) create mode 100644 flight/PiOS/STM32F4xx/pios_overo.c create mode 100644 flight/PiOS/inc/pios_overo.h diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c new file mode 100644 index 000000000..cbeb02945 --- /dev/null +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -0,0 +1,456 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_OVERO OVERO Functions + * @brief PIOS interface to read and write to overo + * @{ + * + * @file pios_overo.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Hardware Abstraction Layer for Overo communications + * @see The GNU Public License (GPL) Version 3 + * @notes + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +/** + * Configures the SPI device to use a double buffered DMA for transferring + * data. At the end of each transfer (NSS goes high) it makes sure to reset + * the DMA counter to the beginning of each packet and swap to the next + * buffer + */ + +#if defined(PIOS_INCLUDE_SPI) + +#include + +static bool PIOS_OVERO_validate(struct pios_overo_dev * com_dev) +{ + /* Should check device magic here */ + return(true); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_overo_dev * PIOS_OVERO_alloc(void) +{ + return (malloc(sizeof(struct pios_overo_dev))); +} +#else +#error Unsupported +#endif + +/** +* Initialises Overo pins +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_Overo_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) +{ + uint32_t init_ssel = 0; + + PIOS_Assert(overo_id); + PIOS_Assert(cfg); + + struct pios_overo_dev * overo_dev; + + overo_dev = (struct pios_overo_dev *) PIOS_OVERO_alloc(); + if (!overo_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + overo_dev->cfg = cfg; + +#if defined(PIOS_INCLUDE_FREERTOS) + vSemaphoreCreateBinary(overo_dev->busy); + xSemaphoreGive(overo_dev->busy); +#endif + + /* Disable callback function */ + overo_dev->callback = NULL; + + /* Set rx/tx dummy bytes to a known value */ + overo_dev->rx_dummy_byte = 0xFF; + overo_dev->tx_dummy_byte = 0xFF; + + /* only legal for single-slave config */ + PIOS_Assert(overo_dev->cfg->slave_count == 1); + init_ssel = 1; + SPI_SSOutputCmd(overo_dev->cfg->regs, (overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) ? ENABLE : DISABLE); + + /* Initialize the GPIO pins */ + /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ + if (overo_dev->cfg->remap) { + GPIO_PinAFConfig(overo_dev->cfg->sclk.gpio, + __builtin_ctz(overo_dev->cfg->sclk.init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_PinAFConfig(overo_dev->cfg->mosi.gpio, + __builtin_ctz(overo_dev->cfg->mosi.init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_PinAFConfig(overo_dev->cfg->miso.gpio, + __builtin_ctz(overo_dev->cfg->miso.init.GPIO_Pin), + overo_dev->cfg->remap); + for (uint32_t i = 0; i < init_ssel; i++) { + GPIO_PinAFConfig(overo_dev->cfg->ssel[i].gpio, + __builtin_ctz(overo_dev->cfg->ssel[i].init.GPIO_Pin), + overo_dev->cfg->remap); + } + } + GPIO_Init(overo_dev->cfg->sclk.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->sclk.init)); + GPIO_Init(overo_dev->cfg->mosi.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->mosi.init)); + GPIO_Init(overo_dev->cfg->miso.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->miso.init)); + + /* Configure DMA for SPI Rx */ + DMA_DeInit(overo_dev->cfg->dma.rx.channel); + DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); + DMA_Init(overo_dev->cfg->dma.rx.channel, (DMA_InitTypeDef*)&(overo_dev->cfg->dma.rx.init)); + + /* Configure DMA for SPI Tx */ + DMA_DeInit(overo_dev->cfg->dma.tx.channel); + DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); + DMA_Init(overo_dev->cfg->dma.tx.channel, (DMA_InitTypeDef*)&(overo_dev->cfg->dma.tx.init)); + + /* Initialize the SPI block */ + SPI_DeInit(overo_dev->cfg->regs); + SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); + + /* Configure CRC calculation */ + if (overo_dev->cfg->use_crc) { + SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); + } else { + SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); + } + + /* Enable SPI */ + SPI_Cmd(overo_dev->cfg->regs, ENABLE); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + + /* Must store this before enabling interrupt */ + *spi_id = (uint32_t)overo_dev; + + /* Configure DMA interrupt */ + NVIC_Init((NVIC_InitTypeDef*)&(overo_dev->cfg->dma.irq.init)); + + return(0); + +out_fail: + return(-1); +} + +/** + * Claim the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_OVERO_ClaimBus(uint32_t spi_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) + + if (xSemaphoreTake(overo_dev->busy, 0xffff) != pdTRUE) + return -1; +#endif + return 0; +} + +/** + * Claim the SPI bus semaphore from an ISR. Has no timeout. + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + * \return -1 if timeout before claiming semaphore + */ +int32_t PIOS_OVERO_ClaimBusISR(uint32_t overo_io) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_overo_dev * overo_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) + + if (xQueueGenericReceive(( xQueueHandle ) overo_dev->busy, NULL, 0x0000 , pdFALSE ) != pdTRUE) + return -1; +#endif + return 0; +} + + +/** + * Release the SPI bus semaphore. Calling the SPI functions does not require this + * \param[in] spi SPI number (0 or 1) + * \return 0 if no error + */ +int32_t PIOS_OVERO_ReleaseBus(uint32_t overo_id) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) + + xSemaphoreGive(overo_dev->busy); +#endif + return 0; +} +/** +* Transfers a block of bytes via DMA. +* \param[in] spi SPI number (0 or 1) +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \param[in] callback pointer to callback function which will be executed +* from DMA channel interrupt once the transfer is finished. +* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will +* block until the transfer is finished. +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +{ + struct pios_overo_dev * overo_dev = (struct pios_spi_dev *)spi_id; + + bool valid = PIOS_SPI_validate(overo_dev); + PIOS_Assert(valid) + + DMA_InitTypeDef dma_init; + + /* Exit if ongoing transfer */ + if (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)) { + return -3; + } + + /* Disable the DMA channels */ + DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); + DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); + + while(DMA_GetCmdStatus(overo_dev->cfg->dma.rx.channel) == ENABLE); + while(DMA_GetCmdStatus(overo_dev->cfg->dma.tx.channel) == ENABLE); + + /* Disable the SPI peripheral */ + /* Initialize the SPI block */ + SPI_DeInit(overo_dev->cfg->regs); + SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); + SPI_Cmd(overo_dev->cfg->regs, DISABLE); + /* Configure CRC calculation */ + if (overo_dev->cfg->use_crc) { + SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); + } else { + SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); + } + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + + /* Set callback function */ + overo_dev->callback = callback; + + /* + * Configure Rx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = overo_dev->cfg->dma.rx.init; + DMA_DeInit(overo_dev->cfg->dma.rx.channel); + if (receive_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) receive_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + overo_dev->rx_dummy_byte = 0xFF; + dma_init.DMA_Memory0BaseAddr = (uint32_t) &overo_dev->rx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + if (overo_dev->cfg->use_crc) { + /* Make sure the CRC error flag is cleared before we start */ + SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); + } + + dma_init.DMA_BufferSize = len; + DMA_Init(overo_dev->cfg->dma.rx.channel, &(dma_init)); + + /* + * Configure Tx channel + */ + + /* Start with the default configuration for this peripheral */ + dma_init = overo_dev->cfg->dma.tx.init; + DMA_DeInit(overo_dev->cfg->dma.tx.channel); + if (send_buffer != NULL) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) send_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + } else { + /* Disable memory addr. increment - bytes written into dummy buffer */ + overo_dev->tx_dummy_byte = 0xFF; + dma_init.DMA_Memory0BaseAddr = (uint32_t) &overo_dev->tx_dummy_byte; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; + } + + if (overo_dev->cfg->use_crc) { + /* The last byte of the payload will be replaced with the CRC8 */ + dma_init.DMA_BufferSize = len - 1; + } else { + dma_init.DMA_BufferSize = len; + } + + DMA_Init(overo_dev->cfg->dma.tx.channel, &(dma_init)); + + /* Enable DMA interrupt if callback function active */ + DMA_ITConfig(overo_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE); + + /* Flush out the CRC registers */ + SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); + (void)SPI_GetCRC(overo_dev->cfg->regs, SPI_CRC_Rx); + SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); + + /* Make sure to flush out the receive buffer */ + (void)SPI_I2S_ReceiveData(overo_dev->cfg->regs); + + if (overo_dev->cfg->use_crc) { + /* Need a 0->1 transition to reset the CRC logic */ + SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); + } + + /* Start DMA transfers */ + DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); + DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); + + /* Reenable the SPI device */ + SPI_Cmd(overo_dev->cfg->regs, ENABLE); + + if (callback) { + /* User has requested a callback, don't wait for the transfer to complete. */ + return 0; + } + + /* Wait until all bytes have been transmitted/received */ + while (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE))); + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)); + + /* Check the CRC on the transfer if enabled. */ + if (overo_dev->cfg->use_crc) { + /* Check the SPI CRC error flag */ + if (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_FLAG_CRCERR)) { + return -4; + } + } + + /* No error */ + return 0; +} + + +/** +* Transfers a block of bytes via PIO or DMA. +* \param[in] spi_id SPI device handle +* \param[in] send_buffer pointer to buffer which should be sent.
+* If NULL, 0xff (all-one) will be sent. +* \param[in] receive_buffer pointer to buffer which should get the received values.
+* If NULL, received bytes will be discarded. +* \param[in] len number of bytes which should be transfered +* \param[in] callback pointer to callback function which will be executed +* from DMA channel interrupt once the transfer is finished. +* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will +* block until the transfer is finished. +* \return >= 0 if no error during transfer +* \return -1 if disabled SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +{ + return SPI_PIO_TransferBlock(spi_id, send_buffer, receive_buffer, len); +} + +/** +* Check if a transfer is in progress +* \param[in] spi SPI number (0 or 1) +* \return >= 0 if no transfer is in progress +* \return -1 if disabled SPI port selected +* \return -2 if unsupported SPI port selected +* \return -3 if function has been called during an ongoing DMA transfer +*/ +int32_t PIOS_OVERO_Busy(uint32_t overo_id) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) + + /* DMA buffer has data or SPI transmit register not empty or SPI is busy*/ + if (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel) || + !SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE) || + SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)) + { + return -3; + } + + return(0); +} + +void PIOS_OVERO_IRQ_Handler(uint32_t spi_id) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) + + // FIXME XXX Only RX channel or better clear flags for both channels? + DMA_ClearFlag(overo_dev->cfg->dma.rx.channel, overo_dev->cfg->dma.irq.flags); + + if(overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (!(SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE))) ; + + /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ + while (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)) ; + } + + if (overo_dev->callback != NULL) { + bool crc_ok = true; + uint8_t crc_val; + + if (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_FLAG_CRCERR)) { + crc_ok = false; + SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); + } + crc_val = SPI_GetCRC(overo_dev->cfg->regs, SPI_CRC_Rx); + overo_dev->callback(crc_ok, crc_val); + } +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h new file mode 100644 index 000000000..71713d933 --- /dev/null +++ b/flight/PiOS/inc/pios_overo.h @@ -0,0 +1,69 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_OVERO Overo Functions + * @{ + * + * @file pios_overo.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Overo functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_OVERO_H +#define PIOS_OVERO_H + +#include +#include + +struct pios_overo_cfg { + SPI_TypeDef *regs; + uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ + SPI_InitTypeDef init; + bool use_crc; + struct stm32_dma dma; + struct stm32_gpio sclk; + struct stm32_gpio miso; + struct stm32_gpio mosi; + uint32_t slave_count; + struct stm32_gpio ssel[]; +}; + +struct pios_overo_dev { + const struct pios_overo_cfg * cfg; + void (*callback) (uint8_t, uint8_t); + uint8_t tx_dummy_byte; + uint8_t rx_dummy_byte; +#if defined(PIOS_INCLUDE_FREERTOS) + xSemaphoreHandle busy; +#else + uint8_t busy; +#endif +}; + +extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); +extern int32_t PIOS_OVERO_SwapBuffer(uint32_t overo_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); + +#endif /* PIOS_OVERO_H */ + +/** + * @} + * @} + */ From a6ba379af9f560a193091dc248004329425184a9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 15:34:54 -0500 Subject: [PATCH 119/508] PIOS_OVERO driver which handles the communications to the overo and ensures the data stays in frame. --- flight/Modules/OveroSync/overosync.c | 63 +-- flight/PiOS/STM32F4xx/pios_overo.c | 399 +++++------------- flight/PiOS/inc/pios_overo.h | 13 +- flight/PiOS/pios.h | 1 + flight/Revolution/System/pios_board.c | 2 +- .../board_hw_defs/revolution/board_hw_defs.c | 24 +- overo | 2 +- 7 files changed, 128 insertions(+), 376 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index c1b3968e8..11612fbda 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -58,8 +58,6 @@ static int32_t packData(uint8_t * data, int32_t length); static int32_t transmitData(); static void transmitDataDone(bool crc_ok, uint8_t crc_val); static void registerObject(UAVObjHandle obj); -// External variables -extern int32_t pios_spi_overo_id; struct dma_transaction { uint8_t tx_buffer[OVEROSYNC_PACKET_SIZE] __attribute__ ((aligned(4))); @@ -83,55 +81,6 @@ struct overosync { struct overosync *overosync; -static void PIOS_OVERO_IRQHandler(); - -static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { - .vector = PIOS_OVERO_IRQHandler, - .line = EXTI_Line15, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI15_10_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line15, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -/** - * On the rising edge of NSS schedule a new transaction. This cannot be - * done by the DMA complete because there is 150 us between that and the - * Overo deasserting the CS line. We don't want to spin that long in an - * isr - */ -void PIOS_OVERO_IRQHandler() -{ - // transmitData must not block to get semaphore for when we get out of - // frame and transaction is still running here. -1 indicates the transaction - // semaphore is blocked and we are still in a transaction, thus a framesync - // error occurred. This shouldn't happen. Race condition? - if(transmitData() == -1) - overosync->framesync_error++; -} - /** * Initialise the telemetry module * \return -1 if initialisation failed @@ -139,8 +88,6 @@ void PIOS_OVERO_IRQHandler() */ int32_t OveroSyncInitialize(void) { - if(pios_spi_overo_id == 0) - return -1; #ifdef MODULE_OVERO_BUILTIN overoEnabled = true; @@ -161,7 +108,6 @@ int32_t OveroSyncInitialize(void) OveroSyncStatsInitialize(); - PIOS_EXTI_Init(&pios_exti_overo_cfg); // Create object queues queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); @@ -183,9 +129,6 @@ int32_t OveroSyncStart(void) return -1; } - if(pios_spi_overo_id == 0) - return -1; - overosync = (struct overosync *) pvPortMalloc(sizeof(*overosync)); if(overosync == NULL) return -1; @@ -302,8 +245,8 @@ static void transmitDataDone(bool crc_ok, uint8_t crc_val) overosync->transaction_done = true; // Parse the data from overo - for (uint32_t i = 0; rx_buffer[0] != 0 && i < sizeof(rx_buffer) ; i++) - UAVTalkProcessInputStream(uavTalkCon, rx_buffer[i]); + //for (uint32_t i = 0; rx_buffer[0] != 0 && i < sizeof(rx_buffer) ; i++) + // UAVTalkProcessInputStream(uavTalkCon, rx_buffer[i]); } /** @@ -393,7 +336,7 @@ static int32_t transmitData() xSemaphoreGiveFromISR(overosync->buffer_lock, &xHigherPriorityTaskWoken); portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); - return PIOS_SPI_TransferBlock(pios_spi_overo_id, (uint8_t *) tx_buffer, (uint8_t *) rx_buffer, sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer), &transmitDataDone) == 0 ? 0 : -3; + return PIOS_Overo_SetNewBuffer((uint8_t *) tx_buffer, (uint8_t *) rx_buffer, sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer), &transmitDataDone) == 0 ? 0 : -3; } /** diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index cbeb02945..8417b269d 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -42,6 +42,42 @@ #include +#define PACKET_SIZE 1024 + +static void PIOS_OVERO_NSS_IRQHandler(); + +static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { + .vector = PIOS_OVERO_NSS_IRQHandler, + .line = EXTI_Line15, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line15, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + + static bool PIOS_OVERO_validate(struct pios_overo_dev * com_dev) { /* Should check device magic here */ @@ -57,37 +93,32 @@ static struct pios_overo_dev * PIOS_OVERO_alloc(void) #error Unsupported #endif +//! Global variable +struct pios_overo_dev * overo_dev; + /** * Initialises Overo pins * \param[in] mode currently only mode 0 supported * \return < 0 if initialisation failed */ -int32_t PIOS_Overo_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) +int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg) { uint32_t init_ssel = 0; - PIOS_Assert(overo_id); PIOS_Assert(cfg); - struct pios_overo_dev * overo_dev; - overo_dev = (struct pios_overo_dev *) PIOS_OVERO_alloc(); if (!overo_dev) goto out_fail; /* Bind the configuration to the device instance */ overo_dev->cfg = cfg; -#if defined(PIOS_INCLUDE_FREERTOS) - vSemaphoreCreateBinary(overo_dev->busy); - xSemaphoreGive(overo_dev->busy); -#endif - /* Disable callback function */ overo_dev->callback = NULL; - /* Set rx/tx dummy bytes to a known value */ - overo_dev->rx_dummy_byte = 0xFF; - overo_dev->tx_dummy_byte = 0xFF; + /* Set a null buffer initially */ + overo_dev->new_tx_buffer = 0; + overo_dev->new_rx_buffer = 0; /* only legal for single-slave config */ PIOS_Assert(overo_dev->cfg->slave_count == 1); @@ -143,12 +174,12 @@ int32_t PIOS_Overo_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) /* Enable SPI interrupts to DMA */ SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); - /* Must store this before enabling interrupt */ - *spi_id = (uint32_t)overo_dev; - /* Configure DMA interrupt */ NVIC_Init((NVIC_InitTypeDef*)&(overo_dev->cfg->dma.irq.init)); + /* Configure the interrupt for rising edge of NSS */ + PIOS_EXTI_Init(&pios_exti_overo_cfg); + return(0); out_fail: @@ -156,296 +187,98 @@ out_fail: } /** - * Claim the SPI bus semaphore. Calling the SPI functions does not require this - * \param[in] spi SPI number (0 or 1) - * \return 0 if no error - * \return -1 if timeout before claiming semaphore + * Transfers a block of bytes via DMA. + * \param[in] overo_id SPI device handle + * \param[in] send_buffer pointer to buffer which should be sent.
+ * If NULL, 0xff (all-one) will be sent. + * \param[in] receive_buffer pointer to buffer which should get the received values.
+ * If NULL, received bytes will be discarded. + * \param[in] len number of bytes which should be transfered + * \param[in] callback pointer to callback function which will be executed + * from DMA channel interrupt once the transfer is finished. + * If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will + * block until the transfer is finished. + * \return >= 0 if no error during transfer + * \return -1 if disabled SPI port selected + * \return -3 if function has been called during an ongoing DMA transfer */ -int32_t PIOS_OVERO_ClaimBus(uint32_t spi_id) +int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) { -#if defined(PIOS_INCLUDE_FREERTOS) - struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; - bool valid = PIOS_OVERO_validate(overo_dev); PIOS_Assert(valid) - if (xSemaphoreTake(overo_dev->busy, 0xffff) != pdTRUE) - return -1; -#endif - return 0; -} - -/** - * Claim the SPI bus semaphore from an ISR. Has no timeout. - * \param[in] spi SPI number (0 or 1) - * \return 0 if no error - * \return -1 if timeout before claiming semaphore - */ -int32_t PIOS_OVERO_ClaimBusISR(uint32_t overo_io) -{ -#if defined(PIOS_INCLUDE_FREERTOS) - struct pios_overo_dev * overo_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - if (xQueueGenericReceive(( xQueueHandle ) overo_dev->busy, NULL, 0x0000 , pdFALSE ) != pdTRUE) - return -1; -#endif - return 0; -} - - -/** - * Release the SPI bus semaphore. Calling the SPI functions does not require this - * \param[in] spi SPI number (0 or 1) - * \return 0 if no error - */ -int32_t PIOS_OVERO_ReleaseBus(uint32_t overo_id) -{ -#if defined(PIOS_INCLUDE_FREERTOS) - struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; - - bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - xSemaphoreGive(overo_dev->busy); -#endif - return 0; -} -/** -* Transfers a block of bytes via DMA. -* \param[in] spi SPI number (0 or 1) -* \param[in] send_buffer pointer to buffer which should be sent.
-* If NULL, 0xff (all-one) will be sent. -* \param[in] receive_buffer pointer to buffer which should get the received values.
-* If NULL, received bytes will be discarded. -* \param[in] len number of bytes which should be transfered -* \param[in] callback pointer to callback function which will be executed -* from DMA channel interrupt once the transfer is finished. -* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will -* block until the transfer is finished. -* \return >= 0 if no error during transfer -* \return -1 if disabled SPI port selected -* \return -3 if function has been called during an ongoing DMA transfer -*/ -static int32_t SPI_DMA_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) -{ - struct pios_overo_dev * overo_dev = (struct pios_spi_dev *)spi_id; - - bool valid = PIOS_SPI_validate(overo_dev); - PIOS_Assert(valid) - - DMA_InitTypeDef dma_init; - - /* Exit if ongoing transfer */ - if (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)) { - return -3; - } - - /* Disable the DMA channels */ - DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); - DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); - - while(DMA_GetCmdStatus(overo_dev->cfg->dma.rx.channel) == ENABLE); - while(DMA_GetCmdStatus(overo_dev->cfg->dma.tx.channel) == ENABLE); - - /* Disable the SPI peripheral */ - /* Initialize the SPI block */ - SPI_DeInit(overo_dev->cfg->regs); - SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); - SPI_Cmd(overo_dev->cfg->regs, DISABLE); - /* Configure CRC calculation */ - if (overo_dev->cfg->use_crc) { - SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); - } else { - SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); - } - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + bool overrun = overo_dev->new_tx_buffer || overo_dev->new_rx_buffer; + /* Cache next buffer */ + overo_dev->new_tx_buffer = (uint32_t) send_buffer; + overo_dev->new_rx_buffer = (uint32_t) receive_buffer; /* Set callback function */ overo_dev->callback = callback; - /* - * Configure Rx channel - */ + /* No error */ + return overrun ? -1 : 0; +} - /* Start with the default configuration for this peripheral */ - dma_init = overo_dev->cfg->dma.rx.init; - DMA_DeInit(overo_dev->cfg->dma.rx.channel); - if (receive_buffer != NULL) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_Memory0BaseAddr = (uint32_t) receive_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - } else { - /* Disable memory addr. increment - bytes written into dummy buffer */ - overo_dev->rx_dummy_byte = 0xFF; - dma_init.DMA_Memory0BaseAddr = (uint32_t) &overo_dev->rx_dummy_byte; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; - } - if (overo_dev->cfg->use_crc) { - /* Make sure the CRC error flag is cleared before we start */ - SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); - } +/** + * On the rising edge of NSS schedule a new transaction. This cannot be + * done by the DMA complete because there is 150 us between that and the + * Overo deasserting the CS line. We don't want to spin that long in an + * isr. + * + * 1. Disable the DMA channel + * 2. Check that the DMA counter is at the end of the buffer (increase an + * error counter if not) + * 3. Reset the DMA counter to the end of the beginning of the buffer + * 4. Swap the buffer + * 5. Enable the DMA channel + */ +void PIOS_OVERO_NSS_IRQHandler() +{ + static uint32_t error_counter = 0; - dma_init.DMA_BufferSize = len; - DMA_Init(overo_dev->cfg->dma.rx.channel, &(dma_init)); + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid) - /* - * Configure Tx channel - */ + /* Disable the SPI peripheral */ + SPI_Cmd(overo_dev->cfg->regs, DISABLE); - /* Start with the default configuration for this peripheral */ - dma_init = overo_dev->cfg->dma.tx.init; - DMA_DeInit(overo_dev->cfg->dma.tx.channel); - if (send_buffer != NULL) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_Memory0BaseAddr = (uint32_t) send_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - } else { - /* Disable memory addr. increment - bytes written into dummy buffer */ - overo_dev->tx_dummy_byte = 0xFF; - dma_init.DMA_Memory0BaseAddr = (uint32_t) &overo_dev->tx_dummy_byte; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable; - } + /* Disable the DMA commands */ + DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); + DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); - if (overo_dev->cfg->use_crc) { - /* The last byte of the payload will be replaced with the CRC8 */ - dma_init.DMA_BufferSize = len - 1; - } else { - dma_init.DMA_BufferSize = len; - } + /* Check that the previous DMA transfer completed */ + if(DMA_GetCurrDataCounter(overo_dev->cfg->dma.tx.channel) || + DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)) + error_counter++; - DMA_Init(overo_dev->cfg->dma.tx.channel, &(dma_init)); + // Activate the new buffer + DMA_MemoryTargetConfig(overo_dev->cfg->dma.tx.channel, overo_dev->new_tx_buffer, DMA_Memory_0); + DMA_MemoryTargetConfig(overo_dev->cfg->dma.rx.channel, overo_dev->new_rx_buffer, DMA_Memory_0); - /* Enable DMA interrupt if callback function active */ - DMA_ITConfig(overo_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE); - - /* Flush out the CRC registers */ - SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); - (void)SPI_GetCRC(overo_dev->cfg->regs, SPI_CRC_Rx); - SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); - - /* Make sure to flush out the receive buffer */ - (void)SPI_I2S_ReceiveData(overo_dev->cfg->regs); - - if (overo_dev->cfg->use_crc) { - /* Need a 0->1 transition to reset the CRC logic */ - SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); - } - - /* Start DMA transfers */ - DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); - DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); - - /* Reenable the SPI device */ + // Enable DMA, Slave first + DMA_SetCurrDataCounter(overo_dev->cfg->dma.tx.channel, PACKET_SIZE); + DMA_SetCurrDataCounter(overo_dev->cfg->dma.rx.channel, PACKET_SIZE); + + /* Reenable the SPI peripheral */ SPI_Cmd(overo_dev->cfg->regs, ENABLE); - if (callback) { - /* User has requested a callback, don't wait for the transfer to complete. */ - return 0; - } + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx, ENABLE); + SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Rx, ENABLE); - /* Wait until all bytes have been transmitted/received */ - while (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)); + /* Enable the DMA endpoints for valid buffers */ + if(overo_dev->new_rx_buffer) + DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); + if(overo_dev->new_tx_buffer) + DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (!(SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE))); + /* Indicate these buffers have been used */ + overo_dev->new_tx_buffer = 0; + overo_dev->new_rx_buffer = 0; - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)); + if (overo_dev->callback != NULL) + overo_dev->callback(true, true); - /* Check the CRC on the transfer if enabled. */ - if (overo_dev->cfg->use_crc) { - /* Check the SPI CRC error flag */ - if (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_FLAG_CRCERR)) { - return -4; - } - } - - /* No error */ - return 0; -} - - -/** -* Transfers a block of bytes via PIO or DMA. -* \param[in] spi_id SPI device handle -* \param[in] send_buffer pointer to buffer which should be sent.
-* If NULL, 0xff (all-one) will be sent. -* \param[in] receive_buffer pointer to buffer which should get the received values.
-* If NULL, received bytes will be discarded. -* \param[in] len number of bytes which should be transfered -* \param[in] callback pointer to callback function which will be executed -* from DMA channel interrupt once the transfer is finished. -* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will -* block until the transfer is finished. -* \return >= 0 if no error during transfer -* \return -1 if disabled SPI port selected -* \return -3 if function has been called during an ongoing DMA transfer -*/ -int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) -{ - return SPI_PIO_TransferBlock(spi_id, send_buffer, receive_buffer, len); -} - -/** -* Check if a transfer is in progress -* \param[in] spi SPI number (0 or 1) -* \return >= 0 if no transfer is in progress -* \return -1 if disabled SPI port selected -* \return -2 if unsupported SPI port selected -* \return -3 if function has been called during an ongoing DMA transfer -*/ -int32_t PIOS_OVERO_Busy(uint32_t overo_id) -{ - struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; - - bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - /* DMA buffer has data or SPI transmit register not empty or SPI is busy*/ - if (DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel) || - !SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE) || - SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)) - { - return -3; - } - - return(0); -} - -void PIOS_OVERO_IRQ_Handler(uint32_t spi_id) -{ - struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; - - bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - // FIXME XXX Only RX channel or better clear flags for both channels? - DMA_ClearFlag(overo_dev->cfg->dma.rx.channel, overo_dev->cfg->dma.irq.flags); - - if(overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) { - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (!(SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_TXE))) ; - - /* Wait for the final bytes of the transfer to complete, including CRC byte(s). */ - while (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_I2S_FLAG_BSY)) ; - } - - if (overo_dev->callback != NULL) { - bool crc_ok = true; - uint8_t crc_val; - - if (SPI_I2S_GetFlagStatus(overo_dev->cfg->regs, SPI_FLAG_CRCERR)) { - crc_ok = false; - SPI_I2S_ClearFlag(overo_dev->cfg->regs, SPI_FLAG_CRCERR); - } - crc_val = SPI_GetCRC(overo_dev->cfg->regs, SPI_CRC_Rx); - overo_dev->callback(crc_ok, crc_val); - } } #endif diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index 71713d933..0af6b84c2 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -49,17 +49,12 @@ struct pios_overo_cfg { struct pios_overo_dev { const struct pios_overo_cfg * cfg; void (*callback) (uint8_t, uint8_t); - uint8_t tx_dummy_byte; - uint8_t rx_dummy_byte; -#if defined(PIOS_INCLUDE_FREERTOS) - xSemaphoreHandle busy; -#else - uint8_t busy; -#endif + uint32_t new_tx_buffer; + uint32_t new_rx_buffer; }; -extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); -extern int32_t PIOS_OVERO_SwapBuffer(uint32_t overo_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); +extern int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg); +extern int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); #endif /* PIOS_OVERO_H */ diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index 6e6e2aa1d..18bc2a665 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -86,6 +86,7 @@ #include #include #include +#include #include #include #include diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index 1fadd7d1e..8afce6619 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -404,7 +404,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_OVERO_SPI) /* Set up the SPI interface to the gyro */ - if (PIOS_SPI_Init(&pios_spi_overo_id, &pios_spi_overo_cfg)) { + if (PIOS_Overo_Init(&pios_overo_cfg)) { PIOS_DEBUG_Assert(0); } #endif diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index 9ce4b9fbb..3a0b13a7a 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -451,10 +451,7 @@ void PIOS_SPI_flash_irq_handler(void) /* SPI3 Interface * - Used for flash communications */ -void PIOS_SPI_overo_irq_handler(void); -void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_overo_irq_handler"))); -void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_SPI_overo_irq_handler"))); -static const struct pios_spi_cfg pios_spi_overo_cfg = { +static const struct pios_overo_cfg pios_overo_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, .init = { @@ -469,18 +466,7 @@ static const struct pios_spi_cfg pios_spi_overo_cfg = { .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, }, .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case RX) - .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), - .init = { - .NVIC_IRQChannel = DMA1_Stream0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - + .dma = { .rx = { .channel = DMA1_Stream0, .init = { @@ -562,12 +548,6 @@ static const struct pios_spi_cfg pios_spi_overo_cfg = { } }, }; -uint32_t pios_spi_overo_id; -void PIOS_SPI_overo_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_overo_id); -} #else uint32_t pios_spi_overo_id = 0; #endif /* PIOS_OVERO_SPI */ diff --git a/overo b/overo index 207effa5b..704c7b291 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 207effa5bdc993b280fa0c5c05aafc10fcfafa28 +Subproject commit 704c7b291a9effd3a9cf189e5fef167c598d79bf From db276538597facbe5437d1857f401aca171580f5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 16:11:23 -0500 Subject: [PATCH 120/508] Make the Overo module use the new driver --- flight/Modules/OveroSync/overosync.c | 77 ++++++++-------------------- flight/PiOS/STM32F4xx/pios_overo.c | 46 ++++++++--------- flight/PiOS/inc/pios_overo.h | 3 +- 3 files changed, 46 insertions(+), 80 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 11612fbda..ef62f5d34 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -55,8 +55,7 @@ static bool overoEnabled; // Private functions static void overoSyncTask(void *parameters); static int32_t packData(uint8_t * data, int32_t length); -static int32_t transmitData(); -static void transmitDataDone(bool crc_ok, uint8_t crc_val); +static void transmitDataDone(); static void registerObject(UAVObjHandle obj); struct dma_transaction { @@ -196,7 +195,10 @@ static void overoSyncTask(void *parameters) portTickType lastUpdateTime = xTaskGetTickCount(); portTickType updateTime; - + + // Set the comms callback + PIOS_Overo_SetCallback(transmitDataDone); + // Loop forever while (1) { // Wait for queue message @@ -229,26 +231,6 @@ static void overoSyncTask(void *parameters) } } -static void transmitDataDone(bool crc_ok, uint8_t crc_val) -{ - uint8_t *rx_buffer; - static signed portBASE_TYPE xHigherPriorityTaskWoken; - - rx_buffer = overosync->transactions[overosync->active_transaction_id].rx_buffer; - - // Release the semaphore and start another transaction (which grabs semaphore again but then - // returns instantly). Because this is called by the DMA ISR we need to be aware of context - // switches. - xSemaphoreGiveFromISR(overosync->transaction_lock, &xHigherPriorityTaskWoken); - portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); - - overosync->transaction_done = true; - - // Parse the data from overo - //for (uint32_t i = 0; rx_buffer[0] != 0 && i < sizeof(rx_buffer) ; i++) - // UAVTalkProcessInputStream(uavTalkCon, rx_buffer[i]); -} - /** * Transmit data buffer to the modem or USB port. * \param[in] data Data buffer to send @@ -256,7 +238,6 @@ static void transmitDataDone(bool crc_ok, uint8_t crc_val) * \return -1 on failure * \return number of bytes transmitted on success */ -uint32_t too_long = 0; static int32_t packData(uint8_t * data, int32_t length) { uint8_t *tx_buffer; @@ -273,49 +254,31 @@ static int32_t packData(uint8_t * data, int32_t length) xSemaphoreGive(overosync->buffer_lock); return -1; } - + // Get offset into buffer and copy contents tx_buffer = overosync->transactions[overosync->loading_transaction_id].tx_buffer + - overosync->write_pointer; + overosync->write_pointer; memcpy(tx_buffer, &tickTime, sizeof(tickTime)); memcpy(tx_buffer + sizeof(tickTime),data,length); overosync->write_pointer += length + sizeof(tickTime); overosync->sent_bytes += length; overosync->sent_objects++; - + xSemaphoreGive(overosync->buffer_lock); -/* // When the NSS line rises while we are packing data then a transaction doesn't start - // because that means we will be here very shortly afterwards (priority of task making that - // not always perfectly true) schedule the transaction here. - if (buffer_swap_failed && (PIOS_DELAY_DiffuS(buffer_swap_timeval) < 50)) { - buffer_swap_failed = false; - transmitData(); - } else if (buffer_swap_failed) { - buffer_swap_failed = false; - too_long++; - } -*/ return length; } -static int32_t transmitData() +/** + * Callback from the overo spi driver at the end of each packet + */ +static void transmitDataDone() { uint8_t *tx_buffer, *rx_buffer; - static signed portBASE_TYPE xHigherPriorityTaskWoken; - - // Get this lock first so we don't swap buffers and then fail - // to start - if (xSemaphoreTake(overosync->transaction_lock, 0) == pdFALSE) - return -1; // Get lock to manipulate buffers if(xSemaphoreTake(overosync->buffer_lock, 0) == pdFALSE) { - xSemaphoreGiveFromISR(overosync->transaction_lock, &xHigherPriorityTaskWoken); - portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); - buffer_swap_failed = true; - buffer_swap_timeval = PIOS_DELAY_GetRaw(); - return -2; + return; } overosync->transaction_done = false; @@ -324,19 +287,21 @@ static int32_t transmitData() overosync->active_transaction_id = overosync->loading_transaction_id; overosync->loading_transaction_id = (overosync->loading_transaction_id + 1) % NELEMENTS(overosync->transactions); - + + // Release the buffer lock + xSemaphoreGive(overosync->buffer_lock); + + // Get the new buffers and configure the overo driver tx_buffer = overosync->transactions[overosync->active_transaction_id].tx_buffer; rx_buffer = overosync->transactions[overosync->active_transaction_id].rx_buffer; + PIOS_Overo_SetNewBuffer((uint8_t *) tx_buffer, (uint8_t *) rx_buffer, + sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer)); + // Prepare the new loading buffer memset(overosync->transactions[overosync->loading_transaction_id].tx_buffer, 0xff, sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)); overosync->write_pointer = 0; - - xSemaphoreGiveFromISR(overosync->buffer_lock, &xHigherPriorityTaskWoken); - portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); - - return PIOS_Overo_SetNewBuffer((uint8_t *) tx_buffer, (uint8_t *) rx_buffer, sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer), &transmitDataDone) == 0 ? 0 : -3; } /** diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 8417b269d..55599ac2c 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -103,8 +103,6 @@ struct pios_overo_dev * overo_dev; */ int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg) { - uint32_t init_ssel = 0; - PIOS_Assert(cfg); overo_dev = (struct pios_overo_dev *) PIOS_OVERO_alloc(); @@ -122,27 +120,23 @@ int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg) /* only legal for single-slave config */ PIOS_Assert(overo_dev->cfg->slave_count == 1); - init_ssel = 1; SPI_SSOutputCmd(overo_dev->cfg->regs, (overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) ? ENABLE : DISABLE); /* Initialize the GPIO pins */ /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ - if (overo_dev->cfg->remap) { - GPIO_PinAFConfig(overo_dev->cfg->sclk.gpio, - __builtin_ctz(overo_dev->cfg->sclk.init.GPIO_Pin), - overo_dev->cfg->remap); - GPIO_PinAFConfig(overo_dev->cfg->mosi.gpio, - __builtin_ctz(overo_dev->cfg->mosi.init.GPIO_Pin), - overo_dev->cfg->remap); - GPIO_PinAFConfig(overo_dev->cfg->miso.gpio, - __builtin_ctz(overo_dev->cfg->miso.init.GPIO_Pin), - overo_dev->cfg->remap); - for (uint32_t i = 0; i < init_ssel; i++) { - GPIO_PinAFConfig(overo_dev->cfg->ssel[i].gpio, - __builtin_ctz(overo_dev->cfg->ssel[i].init.GPIO_Pin), - overo_dev->cfg->remap); - } - } + GPIO_PinAFConfig(overo_dev->cfg->sclk.gpio, + __builtin_ctz(overo_dev->cfg->sclk.init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_PinAFConfig(overo_dev->cfg->mosi.gpio, + __builtin_ctz(overo_dev->cfg->mosi.init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_PinAFConfig(overo_dev->cfg->miso.gpio, + __builtin_ctz(overo_dev->cfg->miso.init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_PinAFConfig(overo_dev->cfg->ssel[0].gpio, + __builtin_ctz(overo_dev->cfg->ssel[0].init.GPIO_Pin), + overo_dev->cfg->remap); + GPIO_Init(overo_dev->cfg->sclk.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->sclk.init)); GPIO_Init(overo_dev->cfg->mosi.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->mosi.init)); GPIO_Init(overo_dev->cfg->miso.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->miso.init)); @@ -202,7 +196,7 @@ out_fail: * \return -1 if disabled SPI port selected * \return -3 if function has been called during an ongoing DMA transfer */ -int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback) +int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len) { bool valid = PIOS_OVERO_validate(overo_dev); PIOS_Assert(valid) @@ -212,13 +206,19 @@ int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buf overo_dev->new_tx_buffer = (uint32_t) send_buffer; overo_dev->new_rx_buffer = (uint32_t) receive_buffer; - /* Set callback function */ - overo_dev->callback = callback; - /* No error */ return overrun ? -1 : 0; } +/** + * Set the callback function + */ +int32_t PIOS_Overo_SetCallback(void *callback) +{ + overo_dev->callback = callback; + return 0; +} + /** * On the rising edge of NSS schedule a new transaction. This cannot be * done by the DMA complete because there is 150 us between that and the diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index 0af6b84c2..4ccc8b39f 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -54,7 +54,8 @@ struct pios_overo_dev { }; extern int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg); -extern int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); +extern int32_t PIOS_Overo_SetCallback(void *callback); +extern int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len); #endif /* PIOS_OVERO_H */ From 9c9143642848cec5e4fb0b35eb6cf10305e67b5e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 16:17:56 -0500 Subject: [PATCH 121/508] Clean up some cruft from Overo module and add a packet counter --- flight/Modules/OveroSync/overosync.c | 12 ++++-------- shared/uavobjectdefinition/overosyncstats.xml | 1 + 2 files changed, 5 insertions(+), 8 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index ef62f5d34..d7ca436f2 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -67,9 +67,8 @@ struct overosync { struct dma_transaction transactions[2]; uint32_t active_transaction_id; uint32_t loading_transaction_id; - xSemaphoreHandle transaction_lock; xSemaphoreHandle buffer_lock; - volatile bool transaction_done; + uint32_t packets; uint32_t sent_bytes; uint32_t write_pointer; uint32_t sent_objects; @@ -132,10 +131,6 @@ int32_t OveroSyncStart(void) if(overosync == NULL) return -1; - overosync->transaction_lock = xSemaphoreCreateMutex(); - if(overosync->transaction_lock == NULL) - return -1; - overosync->buffer_lock = xSemaphoreCreateMutex(); if(overosync->buffer_lock == NULL) return -1; @@ -145,6 +140,7 @@ int32_t OveroSyncStart(void) overosync->write_pointer = 0; overosync->sent_bytes = 0; overosync->framesync_error = 0; + overosync->packets = 0; // Process all registered objects and connect queue for updates UAVObjIterate(®isterObject); @@ -188,7 +184,6 @@ static void overoSyncTask(void *parameters) UAVObjEvent ev; // Kick off SPI transfers (once one is completed another will automatically transmit) - overosync->transaction_done = true; overosync->sent_objects = 0; overosync->failed_objects = 0; overosync->received_objects = 0; @@ -222,6 +217,7 @@ static void overoSyncTask(void *parameters) syncStats.Connected = syncStats.Send > 500 ? OVEROSYNCSTATS_CONNECTED_TRUE : OVEROSYNCSTATS_CONNECTED_FALSE; syncStats.DroppedUpdates = overosync->failed_objects; syncStats.FramesyncErrors = overosync->framesync_error; + syncStats.Packets = overosync->packets; OveroSyncStatsSet(&syncStats); overosync->failed_objects = 0; overosync->sent_bytes = 0; @@ -281,7 +277,7 @@ static void transmitDataDone() return; } - overosync->transaction_done = false; + overosync->packets++; // Swap buffers overosync->active_transaction_id = overosync->loading_transaction_id; diff --git a/shared/uavobjectdefinition/overosyncstats.xml b/shared/uavobjectdefinition/overosyncstats.xml index ec294f7db..b84283a60 100644 --- a/shared/uavobjectdefinition/overosyncstats.xml +++ b/shared/uavobjectdefinition/overosyncstats.xml @@ -6,6 +6,7 @@ + From 2f64124da8a3b407694ff80962c09058eaac0eaa Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 17:21:28 -0500 Subject: [PATCH 122/508] Updates to the pios_overo driver to fully reinit the dma and spi device between packets --- flight/PiOS/STM32F4xx/pios_overo.c | 49 +++++++++++++++++++++--------- flight/PiOS/inc/pios_overo.h | 2 +- 2 files changed, 36 insertions(+), 15 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 55599ac2c..248f6fee9 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -251,34 +251,55 @@ void PIOS_OVERO_NSS_IRQHandler() DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)) error_counter++; - // Activate the new buffer - DMA_MemoryTargetConfig(overo_dev->cfg->dma.tx.channel, overo_dev->new_tx_buffer, DMA_Memory_0); - DMA_MemoryTargetConfig(overo_dev->cfg->dma.rx.channel, overo_dev->new_rx_buffer, DMA_Memory_0); - - // Enable DMA, Slave first - DMA_SetCurrDataCounter(overo_dev->cfg->dma.tx.channel, PACKET_SIZE); - DMA_SetCurrDataCounter(overo_dev->cfg->dma.rx.channel, PACKET_SIZE); - - /* Reenable the SPI peripheral */ - SPI_Cmd(overo_dev->cfg->regs, ENABLE); + /* Disable and initialize the SPI peripheral */ + SPI_DeInit(overo_dev->cfg->regs); + SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); + SPI_Cmd(overo_dev->cfg->regs, DISABLE); /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Rx, ENABLE); + SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); + /* Reinit the DMA channels */ + DMA_InitTypeDef dma_init; + + DMA_DeInit(overo_dev->cfg->dma.rx.channel); + dma_init = overo_dev->cfg->dma.rx.init; + if (overo_dev->new_rx_buffer) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->new_rx_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + dma_init.DMA_BufferSize = PACKET_SIZE; + } + DMA_Init(overo_dev->cfg->dma.rx.channel, &(dma_init)); + + DMA_DeInit(overo_dev->cfg->dma.tx.channel); + dma_init = overo_dev->cfg->dma.tx.init; + if (overo_dev->new_tx_buffer) { + /* Enable memory addr. increment - bytes written into receive buffer */ + dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->new_tx_buffer; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + dma_init.DMA_BufferSize = PACKET_SIZE; + } + DMA_Init(overo_dev->cfg->dma.tx.channel, &(dma_init)); + + /* Make sure to flush out the receive buffer */ + (void)SPI_I2S_ReceiveData(overo_dev->cfg->regs); + /* Enable the DMA endpoints for valid buffers */ if(overo_dev->new_rx_buffer) DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); if(overo_dev->new_tx_buffer) DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); + /* Reenable the SPI peripheral */ + SPI_Cmd(overo_dev->cfg->regs, ENABLE); + /* Indicate these buffers have been used */ overo_dev->new_tx_buffer = 0; overo_dev->new_rx_buffer = 0; if (overo_dev->callback != NULL) - overo_dev->callback(true, true); - + overo_dev->callback(error_counter); } #endif diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index 4ccc8b39f..c9930b3b3 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -48,7 +48,7 @@ struct pios_overo_cfg { struct pios_overo_dev { const struct pios_overo_cfg * cfg; - void (*callback) (uint8_t, uint8_t); + void (*callback) (uint32_t); uint32_t new_tx_buffer; uint32_t new_rx_buffer; }; From 4306afa841f8783043d58c1e1718b5345b601a50 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 17 Jul 2012 17:21:51 -0500 Subject: [PATCH 123/508] Update the module and overosyncstats to track buffer underruns --- flight/Modules/OveroSync/overosync.c | 9 ++++++--- overo | 2 +- shared/uavobjectdefinition/overosyncstats.xml | 1 + 3 files changed, 8 insertions(+), 4 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index d7ca436f2..73c13eea3 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -55,7 +55,7 @@ static bool overoEnabled; // Private functions static void overoSyncTask(void *parameters); static int32_t packData(uint8_t * data, int32_t length); -static void transmitDataDone(); +static void transmitDataDone(uint32_t error_counter); static void registerObject(UAVObjHandle obj); struct dma_transaction { @@ -75,6 +75,7 @@ struct overosync { uint32_t failed_objects; uint32_t received_objects; uint32_t framesync_error; + uint32_t underrun_error; }; struct overosync *overosync; @@ -131,7 +132,7 @@ int32_t OveroSyncStart(void) if(overosync == NULL) return -1; - overosync->buffer_lock = xSemaphoreCreateMutex(); + overosync->buffer_lock = xSemaphoreCreateMutex(); if(overosync->buffer_lock == NULL) return -1; @@ -218,6 +219,7 @@ static void overoSyncTask(void *parameters) syncStats.DroppedUpdates = overosync->failed_objects; syncStats.FramesyncErrors = overosync->framesync_error; syncStats.Packets = overosync->packets; + syncStats.UnderrunErrors = overosync->underrun_error; OveroSyncStatsSet(&syncStats); overosync->failed_objects = 0; overosync->sent_bytes = 0; @@ -268,7 +270,7 @@ static int32_t packData(uint8_t * data, int32_t length) /** * Callback from the overo spi driver at the end of each packet */ -static void transmitDataDone() +static void transmitDataDone(uint32_t error_counter) { uint8_t *tx_buffer, *rx_buffer; @@ -298,6 +300,7 @@ static void transmitDataDone() memset(overosync->transactions[overosync->loading_transaction_id].tx_buffer, 0xff, sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)); overosync->write_pointer = 0; + overosync->underrun_error = error_counter; } /** diff --git a/overo b/overo index 704c7b291..a66f84c87 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 704c7b291a9effd3a9cf189e5fef167c598d79bf +Subproject commit a66f84c87c87a0ceb8b12e8efaacc7445c14b8f4 diff --git a/shared/uavobjectdefinition/overosyncstats.xml b/shared/uavobjectdefinition/overosyncstats.xml index b84283a60..e81fd4068 100644 --- a/shared/uavobjectdefinition/overosyncstats.xml +++ b/shared/uavobjectdefinition/overosyncstats.xml @@ -5,6 +5,7 @@ + From 05427efb2175cb6ee5c875f6c0e48444f2fae318 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 18 Jul 2012 12:42:38 -0500 Subject: [PATCH 124/508] Overo version bump --- overo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/overo b/overo index a66f84c87..5ceb22587 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit a66f84c87c87a0ceb8b12e8efaacc7445c14b8f4 +Subproject commit 5ceb2258737dbd30e5f82f0d5a84a7b6ae861495 From 27ad0fcf6f95b4c15bad3bed7ec324c6d0be6c4a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 19 Jul 2012 21:51:31 -0500 Subject: [PATCH 125/508] Don't allow the system to save while armed --- flight/Modules/System/systemmod.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..879c4ac86 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -216,8 +216,13 @@ static void objectUpdatedCb(UAVObjEvent * ev) ObjectPersistenceGet(&objper); int retval = 1; - // Execute action - if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) { + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + // Execute action if disarmed + if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) { + retval = -1; + } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) { if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) { // Get selected object obj = UAVObjGetByID(objper.ObjectID); From 3eb41d3ef254db5db7db322f1a279f6ccfa50b35 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 19 Jul 2012 22:18:36 -0500 Subject: [PATCH 126/508] When the systemmod callback happens exit if the operation is error or completed --- flight/Modules/System/systemmod.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 879c4ac86..56f4b7820 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -219,6 +219,12 @@ static void objectUpdatedCb(UAVObjEvent * ev) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); + // When this is called because of this method don't do anything + if (objper.Operation == OBJECTPERSISTENCE_OPERATION_ERROR || + objper.Operation == OBJECTPERSISTENCE_OPERATION_COMPLETED) { + return; + } + // Execute action if disarmed if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) { retval = -1; From 1c4c373b86b125a896aac63a0ccaa4fa870d893f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 03:42:09 -0500 Subject: [PATCH 127/508] Begin rewriting pios_overo to look like a standard com layer --- flight/PiOS/STM32F4xx/pios_overo.c | 378 +++++++++++++++-------------- flight/PiOS/inc/pios_overo.h | 11 +- 2 files changed, 199 insertions(+), 190 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 248f6fee9..1f91c64a9 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -44,84 +44,161 @@ #define PACKET_SIZE 1024 -static void PIOS_OVERO_NSS_IRQHandler(); +/* Provide a COM driver */ +static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_OVERO_RegisterTxCallback(uint32_t overo_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail); +static void PIOS_OVERO_RxStart(uint32_t overo_id, uint16_t rx_bytes_avail); -static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { - .vector = PIOS_OVERO_NSS_IRQHandler, - .line = EXTI_Line15, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI15_10_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line15, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, +const struct pios_com_driver pios_overo_com_driver = { + .set_baud = NULL, + .tx_start = PIOS_OVERO_TxStart, + .rx_start = PIOS_OVERO_RxStart, + .bind_tx_cb = PIOS_OVERO_RegisterTxCallback, + .bind_rx_cb = PIOS_OVERO_RegisterRxCallback, }; +//! Data types +enum pios_overo_dev_magic { + PIOS_OVERO_DEV_MAGIC = 0x85A3834A, +}; -static bool PIOS_OVERO_validate(struct pios_overo_dev * com_dev) +struct pios_overo_dev { + enum pios_overo_dev_magic magic; + const struct pios_overo_cfg * cfg; + + int8_t writing_buffer; + uint32_t writing_offset; + + uint8_t tx_buffer[2][PACKET_SIZE]; + uint8_t rx_buffer[2][PACKET_SIZE]; + + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; +}; + +//! Private methods +static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev); +static bool PIOS_OVERO_validate(struct pios_overo_dev * overo_dev); +static struct pios_overo_dev * PIOS_OVERO_alloc(void); + +static bool PIOS_OVERO_validate(struct pios_overo_dev * overo_dev) { - /* Should check device magic here */ - return(true); + return (overo_dev->magic == PIOS_OVERO_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) +#if !defined(PIOS_INCLUDE_FREERTOS) +#error Requires FreeRTOS +#endif /* PIOS_INCLUDE_FREERTOS */ + static struct pios_overo_dev * PIOS_OVERO_alloc(void) { - return (malloc(sizeof(struct pios_overo_dev))); + struct pios_overo_dev * overo_dev; + + overo_dev = (struct pios_overo_dev *)pvPortMalloc(sizeof(*overo_dev)); + if (!overo_dev) return(NULL); + + overo_dev->rx_in_cb = 0; + overo_dev->rx_in_context = 0; + overo_dev->tx_out_cb = 0; + overo_dev->tx_out_context = 0; + overo_dev->magic = PIOS_OVERO_DEV_MAGIC; + return(overo_dev); } -#else -#error Unsupported -#endif - -//! Global variable -struct pios_overo_dev * overo_dev; /** -* Initialises Overo pins -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg) + * Take data from the PIOS_COM buffer and transfer it to the currently inactive DMA + * circular buffer + */ +static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev) { - PIOS_Assert(cfg); + // TODO: How do we protect against the DMA buffer swapping midway through adding data + // to this buffer. If we were writing at the beginning it could cause a weird race. + if (overo_dev->tx_out_cb) { + + uint32_t max_bytes = PACKET_SIZE - overo_dev->writing_offset; + + if (max_bytes > 0) { + bool tx_need_yield = false; + uint16_t bytes_added; + uint8_t *writing_pointer = &overo_dev->tx_buffer[overo_dev->writing_buffer][overo_dev->writing_offset]; + + bytes_added = (overo_dev->tx_out_cb)(overo_dev->tx_out_context, writing_pointer, max_bytes, NULL, &tx_need_yield); + if (tx_need_yield) { + vPortYieldFromISR(); + } + overo_dev->writing_offset += bytes_added; + } + } +} + +/** + * Called at the end of each DMA transaction. Refresh the flag indicating which + * DMA buffer to write new data from the PIOS_COM fifo into the buffer + */ +void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; + PIOS_Assert(PIOS_OVERO_validate(overo_dev)); + + overo_dev->writing_memory = 1 - DMA_GetCurMemoryTarget(overo_dev->cfg->dma.tx.channel); + + // Get data from the Rx buffer and add to the fifo + (void) (overo_dev->rx_in_cb)(overo_dev->rx_in_context, + &overo_dev->rx_buffer[overo_dev->writing_buffer][0], + PACKET_SIZE, NULL, &rx_need_yield); + + // Fill the buffer with known value to prevent rereading these bytes + memset(&overo_dev->rx_buffer[overo_dev->writing_buffer][0], 0xFF, PACKET_SIZE); + + // Fill the buffer with known value to prevent resending any bytes + memset(&overo_dev->tx_buffer[overo_dev->writing_buffer][0], 0xFF, PACKET_SIZE); + + // Load any pending bytes from TX fifo + PIOS_OVERO_WriteData(overo_dev); +} + +/** + * Initialise a single Overo device + */ +int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) +{ + PIOS_DEBUG_Assert(overo_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_overo_dev *overo_dev; + overo_dev = (struct pios_overo_dev *) PIOS_OVERO_alloc(); if (!overo_dev) goto out_fail; - + /* Bind the configuration to the device instance */ overo_dev->cfg = cfg; + overo_dev->writing_buffer = 1; // First writes to second buffer - /* Disable callback function */ - overo_dev->callback = NULL; - - /* Set a null buffer initially */ - overo_dev->new_tx_buffer = 0; - overo_dev->new_rx_buffer = 0; + /* Put buffers to a known state */ + memset(&overo_dev->tx_buffer[0][0], 0xFF, PACKET_SIZE); + memset(&overo_dev->tx_buffer[1][0], 0xFF, PACKET_SIZE); + memset(&overo_dev->rx_buffer[0][0], 0xFF, PACKET_SIZE); + memset(&overo_dev->rx_buffer[1][0], 0xFF, PACKET_SIZE); + /* + * Enable the SPI device + * + * 1. Enable the SPI port + * 2. Enable DMA with circular buffered DMA (validate config) + * 3. Enable the DMA Tx IRQ + */ + + //PIOS_Assert(overo_dev->cfg->dma.tx-> == CIRCULAR); + //PIOS_Assert(overo_dev->cfg->dma.rx-> == CIRCULAR); + /* only legal for single-slave config */ PIOS_Assert(overo_dev->cfg->slave_count == 1); SPI_SSOutputCmd(overo_dev->cfg->regs, (overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) ? ENABLE : DISABLE); - + /* Initialize the GPIO pins */ /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ GPIO_PinAFConfig(overo_dev->cfg->sclk.gpio, @@ -136,170 +213,111 @@ int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg) GPIO_PinAFConfig(overo_dev->cfg->ssel[0].gpio, __builtin_ctz(overo_dev->cfg->ssel[0].init.GPIO_Pin), overo_dev->cfg->remap); - + GPIO_Init(overo_dev->cfg->sclk.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->sclk.init)); GPIO_Init(overo_dev->cfg->mosi.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->mosi.init)); GPIO_Init(overo_dev->cfg->miso.gpio, (GPIO_InitTypeDef*)&(overo_dev->cfg->miso.init)); + + /* Configure circular buffer targets. Configure 0 to be initially active */ + DMA_InitTypeDef dma_init; - /* Configure DMA for SPI Rx */ DMA_DeInit(overo_dev->cfg->dma.rx.channel); - DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); - DMA_Init(overo_dev->cfg->dma.rx.channel, (DMA_InitTypeDef*)&(overo_dev->cfg->dma.rx.init)); - - /* Configure DMA for SPI Tx */ + dma_init = overo_dev->cfg->dma.rx.init; + dma_init.DMA_Memory0BaseAddr = (uin32_t) overo_dev->rx_buffer[0]; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + dma_init.DMA_BufferSize = PACKET_SIZE; + DMA_Init(overo_dev->cfg->dma.rx.channel, &dma_init); + DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.rx.channel, (uin32_t) overo_dev->rx_buffer[1], DMA_Memory_0); + DMA_DeInit(overo_dev->cfg->dma.tx.channel); - DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); - DMA_Init(overo_dev->cfg->dma.tx.channel, (DMA_InitTypeDef*)&(overo_dev->cfg->dma.tx.init)); - + dma_init = overo_dev->cfg->dma.tx.init; + dma_init.DMA_Memory0BaseAddr = (uin32_t) overo_dev->tx_buffer[0]; + dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; + dma_init.DMA_BufferSize = PACKET_SIZE; + DMA_Init(overo_dev->cfg->dma.tx.channel, &dma_init); + DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.tx.channel, (uin32_t) overo_dev->tx_buffer[1], DMA_Memory_0); + /* Initialize the SPI block */ SPI_DeInit(overo_dev->cfg->regs); SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); - + /* Configure CRC calculation */ if (overo_dev->cfg->use_crc) { SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); } else { SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); } - + /* Enable SPI */ SPI_Cmd(overo_dev->cfg->regs, ENABLE); - + /* Enable SPI interrupts to DMA */ SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); - + /* Configure DMA interrupt */ NVIC_Init((NVIC_InitTypeDef*)&(overo_dev->cfg->dma.irq.init)); - /* Configure the interrupt for rising edge of NSS */ - PIOS_EXTI_Init(&pios_exti_overo_cfg); - + /* Enable the DMA channels */ + DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); + DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); + return(0); - + out_fail: return(-1); } -/** - * Transfers a block of bytes via DMA. - * \param[in] overo_id SPI device handle - * \param[in] send_buffer pointer to buffer which should be sent.
- * If NULL, 0xff (all-one) will be sent. - * \param[in] receive_buffer pointer to buffer which should get the received values.
- * If NULL, received bytes will be discarded. - * \param[in] len number of bytes which should be transfered - * \param[in] callback pointer to callback function which will be executed - * from DMA channel interrupt once the transfer is finished. - * If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will - * block until the transfer is finished. - * \return >= 0 if no error during transfer - * \return -1 if disabled SPI port selected - * \return -3 if function has been called during an ongoing DMA transfer - */ -int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len) +static void PIOS_OVERO_RxStart(uint32_t overo_id, uint16_t rx_bytes_avail) { + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - bool overrun = overo_dev->new_tx_buffer || overo_dev->new_rx_buffer; - /* Cache next buffer */ - overo_dev->new_tx_buffer = (uint32_t) send_buffer; - overo_dev->new_rx_buffer = (uint32_t) receive_buffer; - - /* No error */ - return overrun ? -1 : 0; + PIOS_Assert(valid); + + // DMA RX enable (enable IRQ) ? } -/** - * Set the callback function - */ -int32_t PIOS_Overo_SetCallback(void *callback) +static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) { - overo_dev->callback = callback; - return 0; + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid); + + // DMA TX enable (enable IRQ) ? + + // Load any pending bytes from TX fifo + PIOS_OVERO_WriteData(overo_dev); } -/** - * On the rising edge of NSS schedule a new transaction. This cannot be - * done by the DMA complete because there is 150 us between that and the - * Overo deasserting the CS line. We don't want to spin that long in an - * isr. - * - * 1. Disable the DMA channel - * 2. Check that the DMA counter is at the end of the buffer (increase an - * error counter if not) - * 3. Reset the DMA counter to the end of the beginning of the buffer - * 4. Swap the buffer - * 5. Enable the DMA channel - */ -void PIOS_OVERO_NSS_IRQHandler() +static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) { - static uint32_t error_counter = 0; - + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; + bool valid = PIOS_OVERO_validate(overo_dev); - PIOS_Assert(valid) - - /* Disable the SPI peripheral */ - SPI_Cmd(overo_dev->cfg->regs, DISABLE); - - /* Disable the DMA commands */ - DMA_Cmd(overo_dev->cfg->dma.tx.channel, DISABLE); - DMA_Cmd(overo_dev->cfg->dma.rx.channel, DISABLE); - - /* Check that the previous DMA transfer completed */ - if(DMA_GetCurrDataCounter(overo_dev->cfg->dma.tx.channel) || - DMA_GetCurrDataCounter(overo_dev->cfg->dma.rx.channel)) - error_counter++; - - /* Disable and initialize the SPI peripheral */ - SPI_DeInit(overo_dev->cfg->regs); - SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); - SPI_Cmd(overo_dev->cfg->regs, DISABLE); - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); - - /* Reinit the DMA channels */ - DMA_InitTypeDef dma_init; - - DMA_DeInit(overo_dev->cfg->dma.rx.channel); - dma_init = overo_dev->cfg->dma.rx.init; - if (overo_dev->new_rx_buffer) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->new_rx_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - dma_init.DMA_BufferSize = PACKET_SIZE; - } - DMA_Init(overo_dev->cfg->dma.rx.channel, &(dma_init)); - - DMA_DeInit(overo_dev->cfg->dma.tx.channel); - dma_init = overo_dev->cfg->dma.tx.init; - if (overo_dev->new_tx_buffer) { - /* Enable memory addr. increment - bytes written into receive buffer */ - dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->new_tx_buffer; - dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; - dma_init.DMA_BufferSize = PACKET_SIZE; - } - DMA_Init(overo_dev->cfg->dma.tx.channel, &(dma_init)); + PIOS_Assert(valid); - /* Make sure to flush out the receive buffer */ - (void)SPI_I2S_ReceiveData(overo_dev->cfg->regs); - - /* Enable the DMA endpoints for valid buffers */ - if(overo_dev->new_rx_buffer) - DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); - if(overo_dev->new_tx_buffer) - DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + overo_dev->rx_in_context = context; + overo_dev->rx_in_cb = rx_in_cb; +} - /* Reenable the SPI peripheral */ - SPI_Cmd(overo_dev->cfg->regs, ENABLE); +static void PIOS_OVERO_RegisterTxCallback(uint32_t overo_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *)overo_id; - /* Indicate these buffers have been used */ - overo_dev->new_tx_buffer = 0; - overo_dev->new_rx_buffer = 0; - - if (overo_dev->callback != NULL) - overo_dev->callback(error_counter); + bool valid = PIOS_OVERO_validate(overo_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + overo_dev->tx_out_context = context; + overo_dev->tx_out_cb = tx_out_cb; } #endif diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index c9930b3b3..b524cb55e 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -46,16 +46,7 @@ struct pios_overo_cfg { struct stm32_gpio ssel[]; }; -struct pios_overo_dev { - const struct pios_overo_cfg * cfg; - void (*callback) (uint32_t); - uint32_t new_tx_buffer; - uint32_t new_rx_buffer; -}; - -extern int32_t PIOS_Overo_Init(const struct pios_overo_cfg * cfg); -extern int32_t PIOS_Overo_SetCallback(void *callback); -extern int32_t PIOS_Overo_SetNewBuffer(const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len); +extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); #endif /* PIOS_OVERO_H */ From 8fc2d10ea69652b23414919ae6e1af9f6b0c5a93 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 09:32:22 -0500 Subject: [PATCH 128/508] Get the pios_overo driver for pios_com compiling --- flight/PiOS/STM32F4xx/pios_overo.c | 19 +++--- flight/PiOS/inc/pios_overo.h | 18 +----- flight/PiOS/inc/pios_overo_priv.h | 58 +++++++++++++++++++ flight/Revolution/System/pios_board.c | 33 ++++++++--- .../board_hw_defs/revolution/board_hw_defs.c | 43 ++++++++++---- 5 files changed, 129 insertions(+), 42 deletions(-) create mode 100644 flight/PiOS/inc/pios_overo_priv.h diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 1f91c64a9..a0b953444 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -40,7 +40,7 @@ #if defined(PIOS_INCLUDE_SPI) -#include +#include #define PACKET_SIZE 1024 @@ -144,13 +144,18 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; PIOS_Assert(PIOS_OVERO_validate(overo_dev)); - overo_dev->writing_memory = 1 - DMA_GetCurMemoryTarget(overo_dev->cfg->dma.tx.channel); + overo_dev->writing_buffer = 1 - DMA_GetCurrentMemoryTarget(overo_dev->cfg->dma.tx.channel); + bool rx_need_yield; // Get data from the Rx buffer and add to the fifo (void) (overo_dev->rx_in_cb)(overo_dev->rx_in_context, &overo_dev->rx_buffer[overo_dev->writing_buffer][0], PACKET_SIZE, NULL, &rx_need_yield); + if(rx_need_yield) { + vPortYieldFromISR(); + } + // Fill the buffer with known value to prevent rereading these bytes memset(&overo_dev->rx_buffer[overo_dev->writing_buffer][0], 0xFF, PACKET_SIZE); @@ -197,7 +202,7 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) /* only legal for single-slave config */ PIOS_Assert(overo_dev->cfg->slave_count == 1); - SPI_SSOutputCmd(overo_dev->cfg->regs, (overo_dev->cfg->init.SPI_Mode == SPI_Mode_Master) ? ENABLE : DISABLE); + SPI_SSOutputCmd(overo_dev->cfg->regs, DISABLE); /* Initialize the GPIO pins */ /* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */ @@ -223,19 +228,19 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) DMA_DeInit(overo_dev->cfg->dma.rx.channel); dma_init = overo_dev->cfg->dma.rx.init; - dma_init.DMA_Memory0BaseAddr = (uin32_t) overo_dev->rx_buffer[0]; + dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->rx_buffer[0]; dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; dma_init.DMA_BufferSize = PACKET_SIZE; DMA_Init(overo_dev->cfg->dma.rx.channel, &dma_init); - DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.rx.channel, (uin32_t) overo_dev->rx_buffer[1], DMA_Memory_0); + DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.rx.channel, (uint32_t) overo_dev->rx_buffer[1], DMA_Memory_0); DMA_DeInit(overo_dev->cfg->dma.tx.channel); dma_init = overo_dev->cfg->dma.tx.init; - dma_init.DMA_Memory0BaseAddr = (uin32_t) overo_dev->tx_buffer[0]; + dma_init.DMA_Memory0BaseAddr = (uint32_t) overo_dev->tx_buffer[0]; dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable; dma_init.DMA_BufferSize = PACKET_SIZE; DMA_Init(overo_dev->cfg->dma.tx.channel, &dma_init); - DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.tx.channel, (uin32_t) overo_dev->tx_buffer[1], DMA_Memory_0); + DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.tx.channel, (uint32_t) overo_dev->tx_buffer[1], DMA_Memory_0); /* Initialize the SPI block */ SPI_DeInit(overo_dev->cfg->regs); diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index b524cb55e..39f536055 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -30,23 +30,7 @@ #ifndef PIOS_OVERO_H #define PIOS_OVERO_H -#include -#include - -struct pios_overo_cfg { - SPI_TypeDef *regs; - uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ - SPI_InitTypeDef init; - bool use_crc; - struct stm32_dma dma; - struct stm32_gpio sclk; - struct stm32_gpio miso; - struct stm32_gpio mosi; - uint32_t slave_count; - struct stm32_gpio ssel[]; -}; - -extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); +extern void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id); #endif /* PIOS_OVERO_H */ diff --git a/flight/PiOS/inc/pios_overo_priv.h b/flight/PiOS/inc/pios_overo_priv.h new file mode 100644 index 000000000..b1a2e40a4 --- /dev/null +++ b/flight/PiOS/inc/pios_overo_priv.h @@ -0,0 +1,58 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_OVERO Overo Functions + * @{ + * + * @file pios_overo_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Overo functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_OVERO_PRIV_H +#define PIOS_OVERO_PRIV_H + +#include +#include + +extern const struct pios_com_driver pios_overo_com_driver; + +struct pios_overo_cfg { + SPI_TypeDef *regs; + uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ + SPI_InitTypeDef init; + bool use_crc; + struct stm32_dma dma; + struct stm32_gpio sclk; + struct stm32_gpio miso; + struct stm32_gpio mosi; + uint32_t slave_count; + struct stm32_gpio ssel[]; +}; + +extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); + +#endif /* PIOS_OVERO_H */ + +/** + * @} + * @} + */ diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index 8afce6619..32a2f13f0 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -310,6 +310,7 @@ uint32_t pios_com_gps_id = 0; uint32_t pios_com_telem_usb_id = 0; uint32_t pios_com_telem_rf_id = 0; uint32_t pios_com_bridge_id = 0; +uint32_t pios_com_overo_id = 0; /* * Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only @@ -401,13 +402,6 @@ void PIOS_Board_Init(void) { PIOS_Flash_Jedec_Init(pios_spi_accel_id, 1, &flash_m25p_cfg); #endif PIOS_FLASHFS_Init(&flashfs_m25p_cfg); - -#if defined(PIOS_OVERO_SPI) - /* Set up the SPI interface to the gyro */ - if (PIOS_Overo_Init(&pios_overo_cfg)) { - PIOS_DEBUG_Assert(0); - } -#endif /* Initialize UAVObject libraries */ EventDispatcherInitialize(); @@ -786,6 +780,31 @@ void PIOS_Board_Init(void) { break; } +#if defined(PIOS_OVERO_SPI) + /* Set up the SPI based PIOS_COM interface to the overo */ + { + HwSettingsData hwSettings; + HwSettingsGet(&hwSettings); + if(hwSettings.OptionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + if (PIOS_Overo_Init(&pios_overo_id, &pios_overo_cfg)) { + PIOS_DEBUG_Assert(0); + } + + const uint32_t PACKET_SIZE = 1024; + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + } + +#endif + #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); uint32_t pios_gcsrcvr_id; diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index 3a0b13a7a..5c2edadf3 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -447,10 +447,15 @@ void PIOS_SPI_flash_irq_handler(void) } #endif /* PIOS_FLASH_ON_ACCEL */ +#endif /* PIOS_INCLUDE_SPI */ + #if defined(PIOS_OVERO_SPI) /* SPI3 Interface * - Used for flash communications */ +#include +void PIOS_OVERO_irq_handler(void); +void DMA1_Streamr7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); static const struct pios_overo_cfg pios_overo_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, @@ -467,6 +472,17 @@ static const struct pios_overo_cfg pios_overo_cfg = { }, .use_crc = false, .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case TX) + .flags = (DMA_IT_TCIF7 | DMA_IT_TEIF7), //DMA_IT_HTIF7), + .init = { + .NVIC_IRQChannel = DMA1_Stream7_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { .channel = DMA1_Stream0, .init = { @@ -477,13 +493,13 @@ static const struct pios_overo_cfg pios_overo_cfg = { .DMA_MemoryInc = DMA_MemoryInc_Enable, .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, + .DMA_Mode = DMA_Mode_Circular, .DMA_Priority = DMA_Priority_Medium, //TODO: Enable FIFO .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, .tx = { @@ -496,12 +512,12 @@ static const struct pios_overo_cfg pios_overo_cfg = { .DMA_MemoryInc = DMA_MemoryInc_Enable, .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, + .DMA_Mode = DMA_Mode_Circular, .DMA_Priority = DMA_Priority_Medium, .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, }, @@ -547,12 +563,17 @@ static const struct pios_overo_cfg pios_overo_cfg = { }, } }, }; - +uint32_t pios_overo_id = 0; +void PIOS_OVERO_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_OVERO_DMA_irq_handler(pios_overo_id); +} #else -uint32_t pios_spi_overo_id = 0; + #endif /* PIOS_OVERO_SPI */ -#endif /* PIOS_INCLUDE_SPI */ + From 6b3e5573a0871990f8ae5b44e3d2908a3463200e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 09:46:28 -0500 Subject: [PATCH 129/508] The overosync module now uses pios_com interface. --- flight/Modules/OveroSync/overosync.c | 113 ++++---------------------- flight/PiOS/STM32F4xx/pios_overo.c | 15 ++++ flight/PiOS/inc/pios_overo.h | 1 + flight/Revolution/System/pios_board.c | 2 +- 4 files changed, 35 insertions(+), 96 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 73c13eea3..33edfb2ac 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -55,27 +55,17 @@ static bool overoEnabled; // Private functions static void overoSyncTask(void *parameters); static int32_t packData(uint8_t * data, int32_t length); -static void transmitDataDone(uint32_t error_counter); static void registerObject(UAVObjHandle obj); -struct dma_transaction { - uint8_t tx_buffer[OVEROSYNC_PACKET_SIZE] __attribute__ ((aligned(4))); - uint8_t rx_buffer[OVEROSYNC_PACKET_SIZE] __attribute__ ((aligned(4))); -}; +// External variables +extern uint32_t pios_com_overo_id; +extern uint32_t pios_overo_id; struct overosync { - struct dma_transaction transactions[2]; - uint32_t active_transaction_id; - uint32_t loading_transaction_id; - xSemaphoreHandle buffer_lock; - uint32_t packets; uint32_t sent_bytes; - uint32_t write_pointer; uint32_t sent_objects; uint32_t failed_objects; uint32_t received_objects; - uint32_t framesync_error; - uint32_t underrun_error; }; struct overosync *overosync; @@ -132,16 +122,7 @@ int32_t OveroSyncStart(void) if(overosync == NULL) return -1; - overosync->buffer_lock = xSemaphoreCreateMutex(); - if(overosync->buffer_lock == NULL) - return -1; - - overosync->active_transaction_id = 0; - overosync->loading_transaction_id = 0; - overosync->write_pointer = 0; overosync->sent_bytes = 0; - overosync->framesync_error = 0; - overosync->packets = 0; // Process all registered objects and connect queue for updates UAVObjIterate(®isterObject); @@ -192,22 +173,13 @@ static void overoSyncTask(void *parameters) portTickType lastUpdateTime = xTaskGetTickCount(); portTickType updateTime; - // Set the comms callback - PIOS_Overo_SetCallback(transmitDataDone); - // Loop forever while (1) { // Wait for queue message if (xQueueReceive(queue, &ev, portMAX_DELAY) == pdTRUE) { - - // Check it will fit before packetizing - if ((overosync->write_pointer + UAVObjGetNumBytes(ev.obj) + 12) >= - sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)) { - overosync->failed_objects ++; - } else { - // Process event. This calls transmitData - UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); - } + + // Process event. This calls transmitData + UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); updateTime = xTaskGetTickCount(); if(((portTickType) (updateTime - lastUpdateTime)) > 1000) { @@ -217,14 +189,14 @@ static void overoSyncTask(void *parameters) syncStats.Received = 0; syncStats.Connected = syncStats.Send > 500 ? OVEROSYNCSTATS_CONNECTED_TRUE : OVEROSYNCSTATS_CONNECTED_FALSE; syncStats.DroppedUpdates = overosync->failed_objects; - syncStats.FramesyncErrors = overosync->framesync_error; - syncStats.Packets = overosync->packets; - syncStats.UnderrunErrors = overosync->underrun_error; + syncStats.Packets = PIOS_OVERO_GetPacketCount(pios_overo_id); OveroSyncStatsSet(&syncStats); overosync->failed_objects = 0; overosync->sent_bytes = 0; lastUpdateTime = updateTime; } + + // TODO: Check the receive buffer } } } @@ -238,69 +210,20 @@ static void overoSyncTask(void *parameters) */ static int32_t packData(uint8_t * data, int32_t length) { - uint8_t *tx_buffer; - portTickType tickTime = xTaskGetTickCount(); - // Get the lock for manipulating the buffer - xSemaphoreTake(overosync->buffer_lock, portMAX_DELAY); + if( PIOS_COM_SendBuffer(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) + goto fail; + if( PIOS_COM_SendBuffer(pios_com_overo_id, data, length) != 0) + goto fail; + + overosync->sent_bytes += length + 4; - // Check this packet will fit - if ((overosync->write_pointer + length + sizeof(tickTime)) > - sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)) { - overosync->failed_objects ++; - xSemaphoreGive(overosync->buffer_lock); - return -1; - } - - // Get offset into buffer and copy contents - tx_buffer = overosync->transactions[overosync->loading_transaction_id].tx_buffer + - overosync->write_pointer; - memcpy(tx_buffer, &tickTime, sizeof(tickTime)); - memcpy(tx_buffer + sizeof(tickTime),data,length); - overosync->write_pointer += length + sizeof(tickTime); - overosync->sent_bytes += length; - overosync->sent_objects++; - - xSemaphoreGive(overosync->buffer_lock); - return length; -} -/** - * Callback from the overo spi driver at the end of each packet - */ -static void transmitDataDone(uint32_t error_counter) -{ - uint8_t *tx_buffer, *rx_buffer; - - // Get lock to manipulate buffers - if(xSemaphoreTake(overosync->buffer_lock, 0) == pdFALSE) { - return; - } - - overosync->packets++; - - // Swap buffers - overosync->active_transaction_id = overosync->loading_transaction_id; - overosync->loading_transaction_id = (overosync->loading_transaction_id + 1) % - NELEMENTS(overosync->transactions); - - // Release the buffer lock - xSemaphoreGive(overosync->buffer_lock); - - // Get the new buffers and configure the overo driver - tx_buffer = overosync->transactions[overosync->active_transaction_id].tx_buffer; - rx_buffer = overosync->transactions[overosync->active_transaction_id].rx_buffer; - - PIOS_Overo_SetNewBuffer((uint8_t *) tx_buffer, (uint8_t *) rx_buffer, - sizeof(overosync->transactions[overosync->active_transaction_id].tx_buffer)); - - // Prepare the new loading buffer - memset(overosync->transactions[overosync->loading_transaction_id].tx_buffer, 0xff, - sizeof(overosync->transactions[overosync->loading_transaction_id].tx_buffer)); - overosync->write_pointer = 0; - overosync->underrun_error = error_counter; +fail: + overosync->failed_objects++; + return -1; } /** diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index a0b953444..addf57c97 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -70,6 +70,8 @@ struct pios_overo_dev { int8_t writing_buffer; uint32_t writing_offset; + uint32_t packets; + uint8_t tx_buffer[2][PACKET_SIZE]; uint8_t rx_buffer[2][PACKET_SIZE]; @@ -164,6 +166,19 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) // Load any pending bytes from TX fifo PIOS_OVERO_WriteData(overo_dev); + + overo_dev->packets++; +} + +/** + * Debugging information to check how it is runnign + */ +int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; + PIOS_Assert(PIOS_OVERO_validate(overo_dev)); + + return overo_dev->packets; } /** diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index 39f536055..e02e2bac1 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -31,6 +31,7 @@ #define PIOS_OVERO_H extern void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id); +extern int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id); #endif /* PIOS_OVERO_H */ diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index 32a2f13f0..84b868b53 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -786,7 +786,7 @@ void PIOS_Board_Init(void) { HwSettingsData hwSettings; HwSettingsGet(&hwSettings); if(hwSettings.OptionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { - if (PIOS_Overo_Init(&pios_overo_id, &pios_overo_cfg)) { + if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { PIOS_DEBUG_Assert(0); } From fb215fd095b4930fdbb69268037fe3009ccfd97e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 10:17:57 -0500 Subject: [PATCH 130/508] PiOS overo driver wasn't setting it's id and also clearing the DMA IRQ flags --- flight/PiOS/STM32F4xx/pios_overo.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index addf57c97..e8c5b57b1 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -146,6 +146,8 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; PIOS_Assert(PIOS_OVERO_validate(overo_dev)); + DMA_ClearFlag(overo_dev->cfg->dma.tx.channel, overo_dev->cfg->dma.irq.flags); + overo_dev->writing_buffer = 1 - DMA_GetCurrentMemoryTarget(overo_dev->cfg->dma.tx.channel); bool rx_need_yield; @@ -281,6 +283,8 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); DMA_Cmd(overo_dev->cfg->dma.rx.channel, ENABLE); + *overo_id = (uint32_t) overo_dev; + return(0); out_fail: From 6a3c067c18e5bcb68464ec33ffb43add17248e31 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 10:45:20 -0500 Subject: [PATCH 131/508] Zero out the packet counter when pios_over is initialized. --- flight/Modules/OveroSync/overosync.c | 6 +++--- flight/PiOS/STM32F4xx/pios_overo.c | 8 ++------ flight/board_hw_defs/revolution/board_hw_defs.c | 3 ++- 3 files changed, 7 insertions(+), 10 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 33edfb2ac..ea481eac3 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -212,11 +212,11 @@ static int32_t packData(uint8_t * data, int32_t length) { portTickType tickTime = xTaskGetTickCount(); - if( PIOS_COM_SendBuffer(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) +/* if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) goto fail; - if( PIOS_COM_SendBuffer(pios_com_overo_id, data, length) != 0) + if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, data, length) != 0) goto fail; - +*/ overosync->sent_bytes += length + 4; return length; diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index e8c5b57b1..e6fa4e8ed 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -106,6 +106,7 @@ static struct pios_overo_dev * PIOS_OVERO_alloc(void) overo_dev->rx_in_context = 0; overo_dev->tx_out_cb = 0; overo_dev->tx_out_context = 0; + overo_dev->packets = 0; overo_dev->magic = PIOS_OVERO_DEV_MAGIC; return(overo_dev); } @@ -263,12 +264,7 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) SPI_DeInit(overo_dev->cfg->regs); SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); - /* Configure CRC calculation */ - if (overo_dev->cfg->use_crc) { - SPI_CalculateCRC(overo_dev->cfg->regs, ENABLE); - } else { - SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); - } + SPI_CalculateCRC(overo_dev->cfg->regs, DISABLE); /* Enable SPI */ SPI_Cmd(overo_dev->cfg->regs, ENABLE); diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index 5c2edadf3..c54612971 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -455,6 +455,7 @@ void PIOS_SPI_flash_irq_handler(void) */ #include void PIOS_OVERO_irq_handler(void); +void DMA1_Streamr0_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); void DMA1_Streamr7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); static const struct pios_overo_cfg pios_overo_cfg = { .regs = SPI3, @@ -474,7 +475,7 @@ static const struct pios_overo_cfg pios_overo_cfg = { .dma = { .irq = { // Note this is the stream ID that triggers interrupts (in this case TX) - .flags = (DMA_IT_TCIF7 | DMA_IT_TEIF7), //DMA_IT_HTIF7), + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_TCIF7 | DMA_IT_TEIF7), //DMA_IT_HTIF7), .init = { .NVIC_IRQChannel = DMA1_Stream7_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, From 337f0e8bfa1c7025e9a5685efce2a01141cae85e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 10:59:18 -0500 Subject: [PATCH 132/508] Properly enable circular buffering on the overo spi --- flight/PiOS/STM32F4xx/pios_overo.c | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index e6fa4e8ed..aed814cf4 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -251,6 +251,7 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) dma_init.DMA_BufferSize = PACKET_SIZE; DMA_Init(overo_dev->cfg->dma.rx.channel, &dma_init); DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.rx.channel, (uint32_t) overo_dev->rx_buffer[1], DMA_Memory_0); + DMA_DoubleBufferModeCmd(overo_dev->cfg->dma.rx.channel, ENABLE); DMA_DeInit(overo_dev->cfg->dma.tx.channel); dma_init = overo_dev->cfg->dma.tx.init; @@ -259,7 +260,12 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) dma_init.DMA_BufferSize = PACKET_SIZE; DMA_Init(overo_dev->cfg->dma.tx.channel, &dma_init); DMA_DoubleBufferModeConfig(overo_dev->cfg->dma.tx.channel, (uint32_t) overo_dev->tx_buffer[1], DMA_Memory_0); - + DMA_DoubleBufferModeCmd(overo_dev->cfg->dma.tx.channel, ENABLE); + + /* Set the packet size */ + DMA_SetCurrDataCounter(overo_dev->cfg->dma.rx.channel, PACKET_SIZE); + DMA_SetCurrDataCounter(overo_dev->cfg->dma.tx.channel, PACKET_SIZE); + /* Initialize the SPI block */ SPI_DeInit(overo_dev->cfg->regs); SPI_Init(overo_dev->cfg->regs, (SPI_InitTypeDef*)&(overo_dev->cfg->init)); @@ -271,9 +277,10 @@ int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg) /* Enable SPI interrupts to DMA */ SPI_I2S_DMACmd(overo_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE); - + /* Configure DMA interrupt */ NVIC_Init((NVIC_InitTypeDef*)&(overo_dev->cfg->dma.irq.init)); + DMA_ITConfig(overo_dev->cfg->dma.tx.channel, DMA_IT_TC, ENABLE); /* Enable the DMA channels */ DMA_Cmd(overo_dev->cfg->dma.tx.channel, ENABLE); From 88bb73f508b14d547c0fb55ac52bd32dd9c59e95 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 11:14:27 -0500 Subject: [PATCH 133/508] Fix the PIOS_OVERO dma IRQ configuration --- flight/board_hw_defs/revolution/board_hw_defs.c | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index c54612971..b54dd119d 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -455,8 +455,7 @@ void PIOS_SPI_flash_irq_handler(void) */ #include void PIOS_OVERO_irq_handler(void); -void DMA1_Streamr0_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); -void DMA1_Streamr7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); +void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); static const struct pios_overo_cfg pios_overo_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, @@ -473,9 +472,9 @@ static const struct pios_overo_cfg pios_overo_cfg = { }, .use_crc = false, .dma = { - .irq = { + .irq = { // Note this is the stream ID that triggers interrupts (in this case TX) - .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_TCIF7 | DMA_IT_TEIF7), //DMA_IT_HTIF7), + .flags = (DMA_IT_TCIF7), .init = { .NVIC_IRQChannel = DMA1_Stream7_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, @@ -483,7 +482,7 @@ static const struct pios_overo_cfg pios_overo_cfg = { .NVIC_IRQChannelCmd = ENABLE, }, }, - + .rx = { .channel = DMA1_Stream0, .init = { From 5091b160659090645323582844d1c09f7bbab6a7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 11:36:49 -0500 Subject: [PATCH 134/508] Needs work but it's sending data now --- flight/Modules/OveroSync/overosync.c | 6 +++--- flight/PiOS/STM32F4xx/pios_overo.c | 17 +++++++++++++---- flight/Revolution/System/pios_board.c | 1 - 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index ea481eac3..1e563b30e 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -180,7 +180,7 @@ static void overoSyncTask(void *parameters) // Process event. This calls transmitData UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); - + updateTime = xTaskGetTickCount(); if(((portTickType) (updateTime - lastUpdateTime)) > 1000) { // Update stats. This will trigger a local send event too @@ -212,11 +212,11 @@ static int32_t packData(uint8_t * data, int32_t length) { portTickType tickTime = xTaskGetTickCount(); -/* if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) + if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) goto fail; if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, data, length) != 0) goto fail; -*/ + overosync->sent_bytes += length + 4; return length; diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index aed814cf4..b7b83fc77 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -150,8 +150,9 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) DMA_ClearFlag(overo_dev->cfg->dma.tx.channel, overo_dev->cfg->dma.irq.flags); overo_dev->writing_buffer = 1 - DMA_GetCurrentMemoryTarget(overo_dev->cfg->dma.tx.channel); + overo_dev->writing_offset = 0; - bool rx_need_yield; +/* bool rx_need_yield; // Get data from the Rx buffer and add to the fifo (void) (overo_dev->rx_in_cb)(overo_dev->rx_in_context, &overo_dev->rx_buffer[overo_dev->writing_buffer][0], @@ -163,13 +164,21 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) // Fill the buffer with known value to prevent rereading these bytes memset(&overo_dev->rx_buffer[overo_dev->writing_buffer][0], 0xFF, PACKET_SIZE); - +*/ // Fill the buffer with known value to prevent resending any bytes memset(&overo_dev->tx_buffer[overo_dev->writing_buffer][0], 0xFF, PACKET_SIZE); // Load any pending bytes from TX fifo PIOS_OVERO_WriteData(overo_dev); - + + + /*if (overo_dev->tx_out_cb) { + bool tx_need_yield = false; + (overo_dev->tx_out_cb)(overo_dev->tx_out_context, &overo_dev->tx_buffer[overo_dev->writing_buffer][0], PACKET_SIZE, NULL, &tx_need_yield); + if (tx_need_yield) { + vPortYieldFromISR(); + } + }*/ overo_dev->packets++; } @@ -314,7 +323,7 @@ static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) // DMA TX enable (enable IRQ) ? // Load any pending bytes from TX fifo - PIOS_OVERO_WriteData(overo_dev); + //PIOS_OVERO_WriteData(overo_dev); } static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index 84b868b53..7f2a8ebcd 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -789,7 +789,6 @@ void PIOS_Board_Init(void) { if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { PIOS_DEBUG_Assert(0); } - const uint32_t PACKET_SIZE = 1024; uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); From bcdd5a8bba429901d67e9d57108254d8d7993741 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 13:45:31 -0500 Subject: [PATCH 135/508] Fixes to the overo module where it was thinking the fifo buffer writes failed --- flight/Modules/OveroSync/overosync.c | 5 ++--- flight/PiOS/STM32F4xx/pios_overo.c | 19 +++++++++++-------- flight/PiOS/inc/pios_overo.h | 1 + flight/Revolution/System/pios_board.c | 4 ++-- 4 files changed, 16 insertions(+), 13 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 1e563b30e..e0554dadc 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -186,7 +186,6 @@ static void overoSyncTask(void *parameters) // Update stats. This will trigger a local send event too OveroSyncStatsData syncStats; syncStats.Send = overosync->sent_bytes; - syncStats.Received = 0; syncStats.Connected = syncStats.Send > 500 ? OVEROSYNCSTATS_CONNECTED_TRUE : OVEROSYNCSTATS_CONNECTED_FALSE; syncStats.DroppedUpdates = overosync->failed_objects; syncStats.Packets = PIOS_OVERO_GetPacketCount(pios_overo_id); @@ -212,9 +211,9 @@ static int32_t packData(uint8_t * data, int32_t length) { portTickType tickTime = xTaskGetTickCount(); - if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) != 0) + if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) < 0) goto fail; - if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, data, length) != 0) + if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, data, length) < 0) goto fail; overosync->sent_bytes += length + 4; diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index b7b83fc77..5642c2eda 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -171,14 +171,6 @@ void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) // Load any pending bytes from TX fifo PIOS_OVERO_WriteData(overo_dev); - - /*if (overo_dev->tx_out_cb) { - bool tx_need_yield = false; - (overo_dev->tx_out_cb)(overo_dev->tx_out_context, &overo_dev->tx_buffer[overo_dev->writing_buffer][0], PACKET_SIZE, NULL, &tx_need_yield); - if (tx_need_yield) { - vPortYieldFromISR(); - } - }*/ overo_dev->packets++; } @@ -193,6 +185,17 @@ int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id) return overo_dev->packets; } +/** + * Debugging information to check how it is runnign + */ +int32_t PIOS_OVERO_GetWrittenBytes(uint32_t overo_id) +{ + struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; + PIOS_Assert(PIOS_OVERO_validate(overo_dev)); + + return overo_dev->writing_offset; +} + /** * Initialise a single Overo device */ diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index e02e2bac1..9e0f1d4e7 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -32,6 +32,7 @@ extern void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id); extern int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id); +extern int32_t PIOS_OVERO_GetWrittenBytes(uint32_t overo_id); #endif /* PIOS_OVERO_H */ diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index 7f2a8ebcd..df4bfd74a 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -795,8 +795,8 @@ void PIOS_Board_Init(void) { PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + rx_buffer, PACKET_SIZE, + tx_buffer, PACKET_SIZE)) { PIOS_Assert(0); } } From c5904b466742031183e6b0a1cdf865f790b0ff32 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 20 Jul 2012 13:57:47 -0500 Subject: [PATCH 136/508] Clean up the pios_overo driver. Working well now. --- flight/PiOS/STM32F4xx/pios_overo.c | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 5642c2eda..1cb6a26cb 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -120,19 +120,19 @@ static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev) // TODO: How do we protect against the DMA buffer swapping midway through adding data // to this buffer. If we were writing at the beginning it could cause a weird race. if (overo_dev->tx_out_cb) { - - uint32_t max_bytes = PACKET_SIZE - overo_dev->writing_offset; - + + int32_t max_bytes = PACKET_SIZE - overo_dev->writing_offset; + if (max_bytes > 0) { - bool tx_need_yield = false; uint16_t bytes_added; + bool tx_need_yield = false; uint8_t *writing_pointer = &overo_dev->tx_buffer[overo_dev->writing_buffer][overo_dev->writing_offset]; - + bytes_added = (overo_dev->tx_out_cb)(overo_dev->tx_out_context, writing_pointer, max_bytes, NULL, &tx_need_yield); + if (tx_need_yield) { vPortYieldFromISR(); } - overo_dev->writing_offset += bytes_added; } } @@ -145,7 +145,8 @@ static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev) void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id) { struct pios_overo_dev * overo_dev = (struct pios_overo_dev *) overo_id; - PIOS_Assert(PIOS_OVERO_validate(overo_dev)); + if(!PIOS_OVERO_validate(overo_dev)) + return; DMA_ClearFlag(overo_dev->cfg->dma.tx.channel, overo_dev->cfg->dma.irq.flags); @@ -326,7 +327,7 @@ static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) // DMA TX enable (enable IRQ) ? // Load any pending bytes from TX fifo - //PIOS_OVERO_WriteData(overo_dev); + PIOS_OVERO_WriteData(overo_dev); } static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) From 797a4def6a16fc38ea0dd4f5bdc026c65eceb02a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 11:43:31 -0500 Subject: [PATCH 137/508] Do not use the data from the magnetometer if it contains NAN --- flight/Modules/Attitude/revolution/attitude.c | 39 +++++++++++-------- 1 file changed, 22 insertions(+), 17 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 3bebe73c0..cc1ca5a96 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -358,28 +358,30 @@ static int32_t updateAttitudeComplimentary(bool first_run) float brot[3]; float Rbe[3][3]; MagnetometerData mag; - HomeLocationData home; - + Quaternion2R(q, Rbe); MagnetometerGet(&mag); - HomeLocationGet(&home); - rot_mult(Rbe, home.Be, brot); - float mag_len = sqrtf(mag.x * mag.x + mag.y * mag.y + mag.z * mag.z); - mag.x /= mag_len; - mag.y /= mag_len; - mag.z /= mag_len; + // If the mag is producing bad data don't use it (normally bad calibration) + if (mag.x == mag.x && mag.y == mag.y && mag.z == mag.z) { + rot_mult(Rbe, home.Be, brot); - float bmag = sqrtf(brot[0] * brot[0] + brot[1] * brot[1] + brot[2] * brot[2]); - brot[0] /= bmag; - brot[1] /= bmag; - brot[2] /= bmag; + float mag_len = sqrtf(mag.x * mag.x + mag.y * mag.y + mag.z * mag.z); + mag.x /= mag_len; + mag.y /= mag_len; + mag.z /= mag_len; - // Only compute if neither vector is null - if (bmag < 1 || mag_len < 1) - mag_err[0] = mag_err[1] = mag_err[2] = 0; - else - CrossProduct((const float *) &mag.x, (const float *) brot, mag_err); + float bmag = sqrtf(brot[0] * brot[0] + brot[1] * brot[1] + brot[2] * brot[2]); + brot[0] /= bmag; + brot[1] /= bmag; + brot[2] /= bmag; + + // Only compute if neither vector is null + if (bmag < 1 || mag_len < 1) + mag_err[0] = mag_err[1] = mag_err[2] = 0; + else + CrossProduct((const float *) &mag.x, (const float *) brot, mag_err); + } } else { mag_err[0] = mag_err[1] = mag_err[2] = 0; } @@ -568,6 +570,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) GPSVelocityGet(&gpsVelData); HomeLocationGet(&home); + // Discard mag if it has NAN (normally from bad calibration) + mag_updated &= (magData.x == magData.x && magData.y == magData.y && magData.z == magData.z); + // Have a minimum requirement for gps usage gps_updated &= (gpsData.Satellites >= 7) && (gpsData.PDOP <= 4.0f) && (homeLocation.Set == HOMELOCATION_SET_TRUE); From 6eb0fd2b3b045fa5b3df9e55bbc777641fab88e1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 11:50:58 -0500 Subject: [PATCH 138/508] Validate the mag and accel calibration before setting to prevent block NAN on the FC side. --- .../src/plugins/config/configrevowidget.cpp | 61 +++++++++++++++++-- 1 file changed, 57 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 5364fbb44..e9d66cf9a 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -740,15 +740,68 @@ void ConfigRevoWidget::computeScaleBias() revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; - revoCalibration->setData(revoCalibrationData); - position = -1; //set to run again #ifdef SIX_POINT_CAL_ACCEL - m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); + bool good_calibration = true; + + // Check the mag calibration is good + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + + // Check the accel calibration is good + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } #else - m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); + bool good_calibration = true; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } #endif + position = -1; //set to run again } /** From e5bd999975d142bd6bb2f082e9feef4b1369af1d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 13:50:16 -0500 Subject: [PATCH 139/508] Process the settings updates more discretely in revo attitude --- flight/Modules/Attitude/revolution/attitude.c | 57 +++++++++++-------- 1 file changed, 34 insertions(+), 23 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index cc1ca5a96..c703bd243 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -99,6 +99,7 @@ static AttitudeSettingsData attitudeSettings; static HomeLocationData homeLocation; static RevoCalibrationData revoCalibration; static RevoSettingsData revoSettings; +static bool gyroBiasSettingsUpdated = false; const uint32_t SENSOR_QUEUE_SIZE = 10; // Private functions @@ -204,6 +205,8 @@ static void AttitudeTask(void *parameters) // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); settingsUpdatedCb(RevoSettingsHandle()); + settingsUpdatedCb(RevoCalibrationHandle()); + settingsUpdatedCb(HomeLocationHandle()); // Wait for all the sensors be to read vTaskDelay(100); @@ -834,35 +837,43 @@ static int32_t getNED(GPSPositionData * gpsPosition, float * NED) return 0; } -static void settingsUpdatedCb(UAVObjEvent * objEv) +static void settingsUpdatedCb(UAVObjEvent * ev) { - float lat, alt; + // If the object updated was the ObjectPersistence execute requested action + if (ev->obj == RevoCalibrationHandle()) { + RevoCalibrationGet(&revoCalibration); - AttitudeSettingsGet(&attitudeSettings); - RevoCalibrationGet(&revoCalibration); - RevoSettingsGet(&revoSettings); - HomeLocationGet(&homeLocation); + /* When the revo calibration is updated, update the GyroBias object */ + GyrosBiasData gyrosBias; + GyrosBiasGet(&gyrosBias); + gyrosBias.x = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; + gyrosBias.y = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; + gyrosBias.z = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; + GyrosBiasSet(&gyrosBias); - GyrosBiasData gyrosBias; - GyrosBiasGet(&gyrosBias); - gyrosBias.x = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_X] / 100.0f; - gyrosBias.y = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Y] / 100.0f; - gyrosBias.z = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Z] / 100.0f; - GyrosBiasSet(&gyrosBias); + gyroBiasSettingsUpdated = true; - // Compute matrix to convert deltaLLA to NED - lat = homeLocation.Latitude / 10.0e6f * DEG2RAD; - alt = homeLocation.Altitude; + // In case INS currently running + INSSetMagVar(revoCalibration.mag_var); + INSSetAccelVar(revoCalibration.accel_var); + INSSetGyroVar(revoCalibration.gyro_var); + INSSetBaroVar(revoCalibration.baro_var); + } else if (ev->obj == HomeLocationHandle()) { + HomeLocationGet(&homeLocation); - // In case INS currently running - INSSetMagVar(revoCalibration.mag_var); - INSSetAccelVar(revoCalibration.accel_var); - INSSetGyroVar(revoCalibration.gyro_var); - INSSetBaroVar(revoCalibration.baro_var); + // Compute matrix to convert deltaLLA to NED + float lat, alt; + lat = homeLocation.Latitude / 10.0e6f * DEG2RAD; + alt = homeLocation.Altitude; - T[0] = alt+6.378137E6f; - T[1] = cosf(lat)*(alt+6.378137E6f); - T[2] = -1.0f; + T[0] = alt+6.378137E6f; + T[1] = cosf(lat)*(alt+6.378137E6f); + T[2] = -1.0f; + } else if (ev->obj == AttitudeSettingsHandle()) { + AttitudeSettingsGet(&attitudeSettings); + } else if (ev->obj == RevoSettingsHandle()) { + RevoSettingsGet(&revoSettings); + } } /** * @} From 7cdf47c1d47c648decf33bde4b8f3e5997c60105 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 13:51:20 -0500 Subject: [PATCH 140/508] Make the sensors code only apply the GyroBias from the UAVO which is now coming consistently only from the attitude module --- flight/Modules/Attitude/revolution/attitude.c | 44 ++++++++++++++----- flight/Modules/Sensors/sensors.c | 14 +++--- 2 files changed, 38 insertions(+), 20 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index c703bd243..d340a9cfc 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -367,7 +367,7 @@ static int32_t updateAttitudeComplimentary(bool first_run) // If the mag is producing bad data don't use it (normally bad calibration) if (mag.x == mag.x && mag.y == mag.y && mag.z == mag.z) { - rot_mult(Rbe, home.Be, brot); + rot_mult(Rbe, homeLocation.Be, brot); float mag_len = sqrtf(mag.x * mag.x + mag.y * mag.y + mag.z * mag.z); mag.x /= mag_len; @@ -571,6 +571,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) BaroAltitudeGet(&baroData); GPSPositionGet(&gpsData); GPSVelocityGet(&gpsVelData); + GyrosBiasGet(&gyrosBias); HomeLocationGet(&home); // Discard mag if it has NAN (normally from bad calibration) @@ -604,6 +605,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetGyroVar(revoCalibration.gyro_var); INSSetBaroVar(revoCalibration.baro_var); + // Initialize the gyro bias from the settings + INSSetGyroBias(&gyrosBias.x); + xQueueReceive(magQueue, &ev, 100 / portTICK_RATE_MS); MagnetometerGet(&magData); @@ -635,6 +639,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetMagNorth(home.Be); + // Initialize the gyro bias from the settings + INSSetGyroBias(&gyrosBias.x); + GPSPositionData gpsPosition; GPSPositionGet(&gpsPosition); @@ -703,12 +710,21 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) else if(dT <= 0.001f) dT = 0.001f; + // If the gyro bias setting was updated we should reset + // the state estimate of the EKF + if(gyroBiasSettingsUpdated) { + INSSetGyroBias(&gyrosBias.x); + gyroBiasSettingsUpdated = false; + } + // Because the sensor module remove the bias we need to add it - // back in here so that the INS algorithm can track it correctly - GyrosBiasGet(&gyrosBias); - float gyros[3] = {(gyrosData.x - gyrosBias.x) * F_PI / 180.0f, - (gyrosData.y - gyrosBias.y) * F_PI / 180.0f, - (gyrosData.z - gyrosBias.z) * F_PI / 180.0f}; + // back in here so that the INS algorithm can track it correctly + float gyros[3] = {gyrosData.x * F_PI / 180.0f, gyrosData.y * F_PI / 180.0f, gyrosData.z * F_PI / 180.0f}; + if (revoCalibration.BiasCorrectedRaw) { + gyros[0] -= gyrosBias.x * F_PI / 180.0f; + gyros[1] -= gyrosBias.y * F_PI / 180.0f; + gyros[2] -= gyrosBias.z * F_PI / 180.0f; + } // Advance the state estimate INSStatePrediction(gyros, &accelsData.x, dT); @@ -723,11 +739,15 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) Quaternion2RPY(&attitude.q1,&attitude.Roll); AttitudeActualSet(&attitude); - // Copy the gyro bias into the UAVO - gyrosBias.x = -Nav.gyro_bias[0] * 180.0f / F_PI; - gyrosBias.y = -Nav.gyro_bias[1] * 180.0f / F_PI; - gyrosBias.z = -Nav.gyro_bias[2] * 180.0f / F_PI; - GyrosBiasSet(&gyrosBias); + if (revoCalibration.BiasCorrectedRaw && !gyroBiasSettingsUpdated) { + // Copy the gyro bias into the UAVO except when it was updated + // from the settings during the calculation, then consume it + // next cycle + gyrosBias.x = -Nav.gyro_bias[0] * 180.0f / F_PI; + gyrosBias.y = -Nav.gyro_bias[1] * 180.0f / F_PI; + gyrosBias.z = -Nav.gyro_bias[2] * 180.0f / F_PI; + GyrosBiasSet(&gyrosBias); + } // Advance the covariance estimate INSCovariancePrediction(dT); @@ -739,7 +759,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) sensors |= BARO_SENSOR; INSSetMagNorth(home.Be); - + if (gps_updated && outdoor_mode) { INSSetPosVelVar(revoCalibration.gps_var[REVOCALIBRATION_GPS_VAR_POS], revoCalibration.gps_var[REVOCALIBRATION_GPS_VAR_VEL]); diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 5807857a1..31854009a 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -88,7 +88,6 @@ static float mag_bias[3] = {0,0,0}; static float mag_scale[3] = {0,0,0}; static float accel_bias[3] = {0,0,0}; static float accel_scale[3] = {0,0,0}; -static float gyro_bias[3] = {0,0,0}; static float R[3][3] = {{0}}; static int8_t rotate = 0; @@ -377,12 +376,12 @@ static void SensorsTask(void *parameters) } if (bias_correct_gyro) { - // Apply bias correction to the gyros + // Apply bias correction to the gyros from the state estimator GyrosBiasData gyrosBias; GyrosBiasGet(&gyrosBias); - gyrosData.x += gyrosBias.x - gyro_bias[0]; - gyrosData.y += gyrosBias.y - gyro_bias[1]; - gyrosData.z += gyrosBias.z - gyro_bias[2]; + gyrosData.x += gyrosBias.x; + gyrosData.y += gyrosBias.y; + gyrosData.z += gyrosBias.z; } GyrosSet(&gyrosData); @@ -449,9 +448,8 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { accel_scale[0] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_X]; accel_scale[1] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Y]; accel_scale[2] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Z]; - gyro_bias[0] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; - gyro_bias[1] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Y]; - gyro_bias[2] = cal.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Z]; + // Do not store gyros_bias here as that comes from the state estimator and should be + // used from GyroBias directly AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); From 69057a13739c1b829deb858c388e4886b9d588ab Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 13:57:25 -0500 Subject: [PATCH 141/508] No reason to get homeLocation every cycle --- flight/Modules/Attitude/revolution/attitude.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index d340a9cfc..d3170bc84 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -510,7 +510,6 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) GPSPositionData gpsData; GPSVelocityData gpsVelData; GyrosBiasData gyrosBias; - HomeLocationData home; static bool mag_updated = false; static bool baro_updated; @@ -572,7 +571,6 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) GPSPositionGet(&gpsData); GPSVelocityGet(&gpsVelData); GyrosBiasGet(&gyrosBias); - HomeLocationGet(&home); // Discard mag if it has NAN (normally from bad calibration) mag_updated &= (magData.x == magData.x && magData.y == magData.y && magData.z == magData.z); @@ -637,7 +635,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetGyroVar(revoCalibration.gyro_var); INSSetBaroVar(revoCalibration.baro_var); - INSSetMagNorth(home.Be); + INSSetMagNorth(homeLocation.Be); // Initialize the gyro bias from the settings INSSetGyroBias(&gyrosBias.x); @@ -758,7 +756,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) if(baro_updated) sensors |= BARO_SENSOR; - INSSetMagNorth(home.Be); + INSSetMagNorth(homeLocation.Be); if (gps_updated && outdoor_mode) { From 3f4706ad4c753a17fe504911a86c77d7d352c60e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 14:00:52 -0500 Subject: [PATCH 142/508] Make it a critical error when an invalid attitude algorithm is selected --- flight/Modules/Attitude/revolution/attitude.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index d3170bc84..a81da8e63 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -236,7 +236,7 @@ static void AttitudeTask(void *parameters) ret_val = updateAttitudeINSGPS(first_run, false); break; default: - AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE,SYSTEMALARMS_ALARM_ERROR); + AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE,SYSTEMALARMS_ALARM_CRITICAL); break; } From 02dfa7bd8209b386c18ccce3f26856ad4bfad8b4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 14:31:14 -0500 Subject: [PATCH 143/508] Change how the updated settings in attitude are changed to make it easier to initialize them all --- flight/Modules/Attitude/revolution/attitude.c | 26 ++++++++----------- 1 file changed, 11 insertions(+), 15 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index a81da8e63..53213ca95 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -203,10 +203,7 @@ static void AttitudeTask(void *parameters) AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); // Force settings update to make sure rotation loaded - settingsUpdatedCb(AttitudeSettingsHandle()); - settingsUpdatedCb(RevoSettingsHandle()); - settingsUpdatedCb(RevoCalibrationHandle()); - settingsUpdatedCb(HomeLocationHandle()); + settingsUpdatedCb(NULL); // Wait for all the sensors be to read vTaskDelay(100); @@ -857,16 +854,15 @@ static int32_t getNED(GPSPositionData * gpsPosition, float * NED) static void settingsUpdatedCb(UAVObjEvent * ev) { - // If the object updated was the ObjectPersistence execute requested action - if (ev->obj == RevoCalibrationHandle()) { + if (ev == NULL || ev->obj == RevoCalibrationHandle()) { RevoCalibrationGet(&revoCalibration); - + /* When the revo calibration is updated, update the GyroBias object */ GyrosBiasData gyrosBias; GyrosBiasGet(&gyrosBias); gyrosBias.x = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; - gyrosBias.y = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; - gyrosBias.z = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_X]; + gyrosBias.y = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Y]; + gyrosBias.z = revoCalibration.gyro_bias[REVOCALIBRATION_GYRO_BIAS_Z]; GyrosBiasSet(&gyrosBias); gyroBiasSettingsUpdated = true; @@ -876,9 +872,9 @@ static void settingsUpdatedCb(UAVObjEvent * ev) INSSetAccelVar(revoCalibration.accel_var); INSSetGyroVar(revoCalibration.gyro_var); INSSetBaroVar(revoCalibration.baro_var); - } else if (ev->obj == HomeLocationHandle()) { + } + if(ev == NULL || ev->obj == HomeLocationHandle()) { HomeLocationGet(&homeLocation); - // Compute matrix to convert deltaLLA to NED float lat, alt; lat = homeLocation.Latitude / 10.0e6f * DEG2RAD; @@ -887,11 +883,11 @@ static void settingsUpdatedCb(UAVObjEvent * ev) T[0] = alt+6.378137E6f; T[1] = cosf(lat)*(alt+6.378137E6f); T[2] = -1.0f; - } else if (ev->obj == AttitudeSettingsHandle()) { - AttitudeSettingsGet(&attitudeSettings); - } else if (ev->obj == RevoSettingsHandle()) { - RevoSettingsGet(&revoSettings); } + if (ev == NULL || ev->obj == AttitudeSettingsHandle()) + AttitudeSettingsGet(&attitudeSettings); + if (ev == NULL || ev->obj == RevoSettingsHandle()) + RevoSettingsGet(&revoSettings); } /** * @} From 3e33bb49a2581fb3cf43dab18343a27d6fddea5a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 15:11:04 -0500 Subject: [PATCH 144/508] EKF gyro bias into the object now working propely --- flight/Libraries/insgps13state.c | 3 ++ flight/Modules/Attitude/revolution/attitude.c | 32 +++++++++---------- 2 files changed, 18 insertions(+), 17 deletions(-) diff --git a/flight/Libraries/insgps13state.c b/flight/Libraries/insgps13state.c index 52b9c747a..8748ef4c9 100644 --- a/flight/Libraries/insgps13state.c +++ b/flight/Libraries/insgps13state.c @@ -359,6 +359,9 @@ void INSCorrection(float mag_data[3], float Pos[3], float Vel[3], Nav.q[1] = X[7]; Nav.q[2] = X[8]; Nav.q[3] = X[9]; + Nav.gyro_bias[0] = X[10]; + Nav.gyro_bias[1] = X[11]; + Nav.gyro_bias[2] = X[12]; } // ************* CovariancePrediction ************* diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 53213ca95..0325c5c34 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -601,7 +601,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetBaroVar(revoCalibration.baro_var); // Initialize the gyro bias from the settings - INSSetGyroBias(&gyrosBias.x); + float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + INSSetGyroBias(gyro_bias); xQueueReceive(magQueue, &ev, 100 / portTICK_RATE_MS); MagnetometerGet(&magData); @@ -635,7 +636,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetMagNorth(homeLocation.Be); // Initialize the gyro bias from the settings - INSSetGyroBias(&gyrosBias.x); + float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + INSSetGyroBias(gyro_bias); GPSPositionData gpsPosition; GPSPositionGet(&gpsPosition); @@ -708,7 +710,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // If the gyro bias setting was updated we should reset // the state estimate of the EKF if(gyroBiasSettingsUpdated) { - INSSetGyroBias(&gyrosBias.x); + float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + INSSetGyroBias(gyro_bias); gyroBiasSettingsUpdated = false; } @@ -734,16 +737,6 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) Quaternion2RPY(&attitude.q1,&attitude.Roll); AttitudeActualSet(&attitude); - if (revoCalibration.BiasCorrectedRaw && !gyroBiasSettingsUpdated) { - // Copy the gyro bias into the UAVO except when it was updated - // from the settings during the calculation, then consume it - // next cycle - gyrosBias.x = -Nav.gyro_bias[0] * 180.0f / F_PI; - gyrosBias.y = -Nav.gyro_bias[1] * 180.0f / F_PI; - gyrosBias.z = -Nav.gyro_bias[2] * 180.0f / F_PI; - GyrosBiasSet(&gyrosBias); - } - // Advance the covariance estimate INSCovariancePrediction(dT); @@ -819,10 +812,15 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) velocityActual.East = Nav.Vel[1]; velocityActual.Down = Nav.Vel[2]; VelocityActualSet(&velocityActual); - - if(fabs(Nav.gyro_bias[0]) > 0.1f || fabs(Nav.gyro_bias[1]) > 0.1f || fabs(Nav.gyro_bias[2]) > 0.1f) { - float zeros[3] = {0.0f,0.0f,0.0f}; - INSSetGyroBias(zeros); + + if (revoCalibration.BiasCorrectedRaw == REVOCALIBRATION_BIASCORRECTEDRAW_TRUE && !gyroBiasSettingsUpdated) { + // Copy the gyro bias into the UAVO except when it was updated + // from the settings during the calculation, then consume it + // next cycle + gyrosBias.x = -Nav.gyro_bias[0] * 180.0f / F_PI; + gyrosBias.y = -Nav.gyro_bias[1] * 180.0f / F_PI; + gyrosBias.z = -Nav.gyro_bias[2] * 180.0f / F_PI; + GyrosBiasSet(&gyrosBias); } return 0; From e239424dddf6e400b35fcaea6c01e51e6f82f73c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 15:12:45 -0500 Subject: [PATCH 145/508] Fix some typos in the GCS calibration --- .../src/plugins/config/configrevowidget.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index e9d66cf9a..84be939d0 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -942,15 +942,15 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) Q_ASSERT(revoCalibration); if(revoCalibration) { RevoCalibration::DataFields revoCalData = revoCalibration->getData(); - revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_X] = listVar(accel_accum_x); - revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_Y] = listVar(accel_accum_y); - revoCalData.accel_var[RevoCalibration::ACCEL_BIAS_Z] = listVar(accel_accum_z); - revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_X] = listVar(gyro_accum_x); - revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_Y] = listVar(gyro_accum_y); - revoCalData.gyro_var[RevoCalibration::GYRO_BIAS_Z] = listVar(gyro_accum_z); - revoCalData.mag_var[RevoCalibration::MAG_BIAS_X] = listVar(mag_accum_x); - revoCalData.mag_var[RevoCalibration::MAG_BIAS_Y] = listVar(mag_accum_y); - revoCalData.mag_var[RevoCalibration::MAG_BIAS_Z] = listVar(mag_accum_z); + revoCalData.accel_var[RevoCalibration::ACCEL_VAR_X] = listVar(accel_accum_x); + revoCalData.accel_var[RevoCalibration::ACCEL_VAR_Y] = listVar(accel_accum_y); + revoCalData.accel_var[RevoCalibration::ACCEL_VAR_Z] = listVar(accel_accum_z); + revoCalData.gyro_var[RevoCalibration::GYRO_VAR_X] = listVar(gyro_accum_x); + revoCalData.gyro_var[RevoCalibration::GYRO_VAR_Y] = listVar(gyro_accum_y); + revoCalData.gyro_var[RevoCalibration::GYRO_VAR_Z] = listVar(gyro_accum_z); + revoCalData.mag_var[RevoCalibration::MAG_VAR_X] = listVar(mag_accum_x); + revoCalData.mag_var[RevoCalibration::MAG_VAR_Y] = listVar(mag_accum_y); + revoCalData.mag_var[RevoCalibration::MAG_VAR_Z] = listVar(mag_accum_z); revoCalibration->setData(revoCalData); } } From d36663dbbd62d95564362ddbf1fe1a2d0e678069 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 15:14:45 -0500 Subject: [PATCH 146/508] Treat the GyroBias UAVO like a state estimate of the actual gyro bias so now we subtract that from the raw sensor readings to get the Gyros UAVO value --- flight/Modules/Attitude/revolution/attitude.c | 24 +++++++++---------- flight/Modules/Sensors/sensors.c | 6 ++--- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 0325c5c34..5ef3dc4d3 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -389,9 +389,9 @@ static int32_t updateAttitudeComplimentary(bool first_run) // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s GyrosBiasData gyrosBias; GyrosBiasGet(&gyrosBias); - gyrosBias.x += accel_err[0] * attitudeSettings.AccelKi; - gyrosBias.y += accel_err[1] * attitudeSettings.AccelKi; - gyrosBias.z += mag_err[2] * magKi; + gyrosBias.x -= accel_err[0] * attitudeSettings.AccelKi; + gyrosBias.y -= accel_err[1] * attitudeSettings.AccelKi; + gyrosBias.z -= mag_err[2] * magKi; GyrosBiasSet(&gyrosBias); // Correct rates based on error, integral component dealt with in updateSensors @@ -601,7 +601,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetBaroVar(revoCalibration.baro_var); // Initialize the gyro bias from the settings - float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + float gyro_bias[3] = {gyrosBias.x * F_PI / 180.0f, gyrosBias.y * F_PI / 180.0f, gyrosBias.z * F_PI / 180.0f}; INSSetGyroBias(gyro_bias); xQueueReceive(magQueue, &ev, 100 / portTICK_RATE_MS); @@ -636,7 +636,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetMagNorth(homeLocation.Be); // Initialize the gyro bias from the settings - float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + float gyro_bias[3] = {gyrosBias.x * F_PI / 180.0f, gyrosBias.y * F_PI / 180.0f, gyrosBias.z * F_PI / 180.0f}; INSSetGyroBias(gyro_bias); GPSPositionData gpsPosition; @@ -710,7 +710,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // If the gyro bias setting was updated we should reset // the state estimate of the EKF if(gyroBiasSettingsUpdated) { - float gyro_bias[3] = {-gyrosBias.x * F_PI / 180.0f, -gyrosBias.y * F_PI / 180.0f, -gyrosBias.z * F_PI / 180.0f}; + float gyro_bias[3] = {gyrosBias.x * F_PI / 180.0f, gyrosBias.y * F_PI / 180.0f, gyrosBias.z * F_PI / 180.0f}; INSSetGyroBias(gyro_bias); gyroBiasSettingsUpdated = false; } @@ -719,9 +719,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // back in here so that the INS algorithm can track it correctly float gyros[3] = {gyrosData.x * F_PI / 180.0f, gyrosData.y * F_PI / 180.0f, gyrosData.z * F_PI / 180.0f}; if (revoCalibration.BiasCorrectedRaw) { - gyros[0] -= gyrosBias.x * F_PI / 180.0f; - gyros[1] -= gyrosBias.y * F_PI / 180.0f; - gyros[2] -= gyrosBias.z * F_PI / 180.0f; + gyros[0] += gyrosBias.x * F_PI / 180.0f; + gyros[1] += gyrosBias.y * F_PI / 180.0f; + gyros[2] += gyrosBias.z * F_PI / 180.0f; } // Advance the state estimate @@ -817,9 +817,9 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // Copy the gyro bias into the UAVO except when it was updated // from the settings during the calculation, then consume it // next cycle - gyrosBias.x = -Nav.gyro_bias[0] * 180.0f / F_PI; - gyrosBias.y = -Nav.gyro_bias[1] * 180.0f / F_PI; - gyrosBias.z = -Nav.gyro_bias[2] * 180.0f / F_PI; + gyrosBias.x = Nav.gyro_bias[0] * 180.0f / F_PI; + gyrosBias.y = Nav.gyro_bias[1] * 180.0f / F_PI; + gyrosBias.z = Nav.gyro_bias[2] * 180.0f / F_PI; GyrosBiasSet(&gyrosBias); } diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 31854009a..7addc0dad 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -379,9 +379,9 @@ static void SensorsTask(void *parameters) // Apply bias correction to the gyros from the state estimator GyrosBiasData gyrosBias; GyrosBiasGet(&gyrosBias); - gyrosData.x += gyrosBias.x; - gyrosData.y += gyrosBias.y; - gyrosData.z += gyrosBias.z; + gyrosData.x -= gyrosBias.x; + gyrosData.y -= gyrosBias.y; + gyrosData.z -= gyrosBias.z; } GyrosSet(&gyrosData); From fa68c0422d30acf8af477b494e34bc364bdb851e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 15:44:23 -0500 Subject: [PATCH 147/508] Make sure to always compare BiasCorrectedRaw against its enum. Also reversed the order of TRUE,FALSE in the definition to make it safer anyway. --- flight/Modules/Attitude/revolution/attitude.c | 2 +- flight/Modules/Sensors/sensors.c | 2 +- shared/uavobjectdefinition/revocalibration.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 5ef3dc4d3..31c38150d 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -718,7 +718,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // Because the sensor module remove the bias we need to add it // back in here so that the INS algorithm can track it correctly float gyros[3] = {gyrosData.x * F_PI / 180.0f, gyrosData.y * F_PI / 180.0f, gyrosData.z * F_PI / 180.0f}; - if (revoCalibration.BiasCorrectedRaw) { + if (revoCalibration.BiasCorrectedRaw = REVOCALIBRATION_BIASCORRECTEDRAW_TRUE) { gyros[0] += gyrosBias.x * F_PI / 180.0f; gyros[1] += gyrosBias.y * F_PI / 180.0f; gyros[2] += gyrosBias.z * F_PI / 180.0f; diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 7addc0dad..c5fe3f351 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -453,7 +453,7 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); - bias_correct_gyro = (attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE); + bias_correct_gyro = (cal.BiasCorrectedRaw == REVOCALIBRATION_BIASCORRECTEDRAW_TRUE); // Indicates not to expend cycles on rotation if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && diff --git a/shared/uavobjectdefinition/revocalibration.xml b/shared/uavobjectdefinition/revocalibration.xml index 5a5f4b42e..ee5722b6f 100644 --- a/shared/uavobjectdefinition/revocalibration.xml +++ b/shared/uavobjectdefinition/revocalibration.xml @@ -1,7 +1,7 @@ Settings for the INS to control the algorithm and what is updated - + From 5649813c2bbe4b438aa3ba7c5623e4d833786610 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 15:44:23 -0500 Subject: [PATCH 148/508] Make sure to always compare BiasCorrectedRaw against its enum. Also reversed the order of TRUE,FALSE in the definition to make it safer anyway. --- flight/Modules/Attitude/revolution/attitude.c | 2 +- flight/Modules/Sensors/sensors.c | 2 +- shared/uavobjectdefinition/revocalibration.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index 5ef3dc4d3..cc175cb48 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -718,7 +718,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) // Because the sensor module remove the bias we need to add it // back in here so that the INS algorithm can track it correctly float gyros[3] = {gyrosData.x * F_PI / 180.0f, gyrosData.y * F_PI / 180.0f, gyrosData.z * F_PI / 180.0f}; - if (revoCalibration.BiasCorrectedRaw) { + if (revoCalibration.BiasCorrectedRaw == REVOCALIBRATION_BIASCORRECTEDRAW_TRUE) { gyros[0] += gyrosBias.x * F_PI / 180.0f; gyros[1] += gyrosBias.y * F_PI / 180.0f; gyros[2] += gyrosBias.z * F_PI / 180.0f; diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 7addc0dad..c5fe3f351 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -453,7 +453,7 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); - bias_correct_gyro = (attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE); + bias_correct_gyro = (cal.BiasCorrectedRaw == REVOCALIBRATION_BIASCORRECTEDRAW_TRUE); // Indicates not to expend cycles on rotation if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && diff --git a/shared/uavobjectdefinition/revocalibration.xml b/shared/uavobjectdefinition/revocalibration.xml index 5a5f4b42e..ee5722b6f 100644 --- a/shared/uavobjectdefinition/revocalibration.xml +++ b/shared/uavobjectdefinition/revocalibration.xml @@ -1,7 +1,7 @@ Settings for the INS to control the algorithm and what is updated - + From 0c054a1e62d34bad325e078f4761e6b896bf4055 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 21 Jul 2012 17:25:06 -0500 Subject: [PATCH 149/508] Speed up attitude loop on Revo to 666 Hz --- flight/Revolution/System/pios_board.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index df4bfd74a..b9360bfef 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -217,7 +217,7 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { .exti_cfg = &pios_exti_mpu6000_cfg, .Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT, // Clock at 8 khz, downsampled by 8 for 1khz - .Smpl_rate_div = 15, + .Smpl_rate_div = 11, .interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD, .interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY, .User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C, From 9c512261e67deb39dc493579b9f7db890f54b9ed Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 01:02:14 -0500 Subject: [PATCH 150/508] When in indoor mode reset the baro offset to zero --- flight/Modules/Attitude/revolution/attitude.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/Modules/Attitude/revolution/attitude.c b/flight/Modules/Attitude/revolution/attitude.c index cc175cb48..e4380b2ab 100644 --- a/flight/Modules/Attitude/revolution/attitude.c +++ b/flight/Modules/Attitude/revolution/attitude.c @@ -776,6 +776,7 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) NEDPositionSet(&nedPos); } else if (!outdoor_mode) { + baroOffset = 0; INSSetPosVelVar(1e2f, 1e2f); vel[0] = vel[1] = vel[2] = 0; NED[0] = NED[1] = 0; From fa4adf16307b0cd6fadb8b79cd20982029baeeb2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 01:17:06 -0500 Subject: [PATCH 151/508] A few of the UBX types were missing a struct for the type. --- flight/Modules/GPS/UBX.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/GPS/UBX.c b/flight/Modules/GPS/UBX.c index 536236a6b..92d5e08bf 100644 --- a/flight/Modules/GPS/UBX.c +++ b/flight/Modules/GPS/UBX.c @@ -249,7 +249,7 @@ void parse_ubx_nav_velned (struct UBX_NAV_VELNED *velned, GPSPositionData *GpsPo } #if !defined(PIOS_GPS_MINIMAL) -void parse_ubx_nav_timeutc (UBX_NAV_TIMEUTC *timeutc) +void parse_ubx_nav_timeutc (struct UBX_NAV_TIMEUTC *timeutc) { if (!(timeutc->valid & TIMEUTC_VALIDUTC)) return; @@ -268,7 +268,7 @@ void parse_ubx_nav_timeutc (UBX_NAV_TIMEUTC *timeutc) #endif #if !defined(PIOS_GPS_MINIMAL) -void parse_ubx_nav_svinfo (UBX_NAV_SVINFO *svinfo) +void parse_ubx_nav_svinfo (struct UBX_NAV_SVINFO *svinfo) { uint8_t chan; GPSSatellitesData svdata; From 57a554f7eac3abe7e1e0b733005ddac445251e99 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 01:17:29 -0500 Subject: [PATCH 152/508] Enable the GPS UBX/NMEA support --- flight/Revolution/System/inc/pios_config.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index 953683f51..4bb7be2a7 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -75,6 +75,10 @@ #define PIOS_INCLUDE_COM_FLEXI #define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +#define PIOS_GPS_SETS_HOMELOCATION + #define PIOS_OVERO_SPI /* Supported receiver interfaces */ #define PIOS_INCLUDE_RCVR From d8e0cbc78fb2804e1cca341ffd79666b2a5a0cf1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 02:17:58 -0500 Subject: [PATCH 153/508] Make inadequate lock a warning instead of error/critical from GPS. This allows flying indoors. --- flight/Modules/GPS/GPS.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 5851ac10d..c3d871318 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -232,7 +232,7 @@ static void gpsTask(void *parameters) // either the GPS is not plugged in or a hardware problem or the GPS has locked up. uint8_t status = GPSPOSITION_STATUS_NOGPS; GPSPositionStatusSet(&status); - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); + AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); } else { // we appear to be receiving GPS sentences OK, we've had an update //criteria for GPS-OK taken from this post... @@ -250,7 +250,7 @@ static void gpsTask(void *parameters) } else if (gpsposition.Status == GPSPOSITION_STATUS_FIX3D) AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); else - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); + AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); } } From 05643d2f2b0ed829eac6c04fc96204f6228d58d3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 02:46:16 -0500 Subject: [PATCH 154/508] Overo bump --- overo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/overo b/overo index 5ceb22587..584f4978e 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 5ceb2258737dbd30e5f82f0d5a84a7b6ae861495 +Subproject commit 584f4978ef2d8912f06881e784dc1fd26e707c77 From cf6b49535ad648d1115a2838fefb382acb298ac5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 09:19:28 -0500 Subject: [PATCH 155/508] Add pios_struct_helper to PiOS.osx --- flight/PiOS.osx/inc/pios_struct_helper.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 flight/PiOS.osx/inc/pios_struct_helper.h diff --git a/flight/PiOS.osx/inc/pios_struct_helper.h b/flight/PiOS.osx/inc/pios_struct_helper.h new file mode 100644 index 000000000..6196d9b26 --- /dev/null +++ b/flight/PiOS.osx/inc/pios_struct_helper.h @@ -0,0 +1,12 @@ +/* Taken from include/linux/kernel.h from the Linux kernel tree */ + +/** + * container_of - cast a member of a structure out to the containing structure + * @ptr: the pointer to the member. + * @type: the type of the container struct this is embedded in. + * @member: the name of the member within the struct. + * + */ +#define container_of(ptr, type, member) ({ \ + const typeof( ((type *)0)->member ) *__mptr = (ptr); \ + (type *)( (char *)__mptr - offsetof(type,member) );}) From 7522bd07ba2f8eff8175924110a444104252d036 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 09:42:53 -0500 Subject: [PATCH 156/508] Disable the FLASH_FREERTOS flag for revolution so that it doesn't try and use vTaskDelay while erasing flash. --- flight/Revolution/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index 4bb7be2a7..a84772031 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -66,7 +66,7 @@ #define PIOS_INCLUDE_ETASV3 //#define PIOS_INCLUDE_HCSR04 #define PIOS_FLASH_ON_ACCEL /* true for second revo */ -#define FLASH_FREERTOS + /* Com systems to include */ #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_COM_TELEM From 8f8ae5bacb430cb41938dd22d4a88dc4a75e9b14 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 10:01:32 -0500 Subject: [PATCH 157/508] For revolution we MUST initialize teh GPS objects all the time or attitude will fail --- flight/Modules/GPS/GPS.c | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index c3d871318..de2dda5a9 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -138,6 +138,16 @@ int32_t GPSInitialize(void) gpsEnabled = false; #endif +#if defined(REVOLUTION) + // These objects MUST be initialized for Revolution + // because the rest of the system expects to just + // attach to their queues + GPSPositionInitialize(); + GPSVelocityInitialize(); + GPSTimeInitialize(); + HomeLocationInitialize(); +#endif + if (gpsPort && gpsEnabled) { GPSPositionInitialize(); GPSVelocityInitialize(); From 26f07c21f6a2a601b6f08e0c1a9625e3dd5ad915 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 10:07:42 -0500 Subject: [PATCH 158/508] Fix the pios_overo driver for compiling against the bootloader --- flight/PiOS/STM32F4xx/pios_overo.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 1cb6a26cb..1e25ab534 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -81,6 +81,7 @@ struct pios_overo_dev { uint32_t tx_out_context; }; +#if defined(PIOS_INCLUDE_FREERTOS) //! Private methods static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev); static bool PIOS_OVERO_validate(struct pios_overo_dev * overo_dev); @@ -91,10 +92,6 @@ static bool PIOS_OVERO_validate(struct pios_overo_dev * overo_dev) return (overo_dev->magic == PIOS_OVERO_DEV_MAGIC); } -#if !defined(PIOS_INCLUDE_FREERTOS) -#error Requires FreeRTOS -#endif /* PIOS_INCLUDE_FREERTOS */ - static struct pios_overo_dev * PIOS_OVERO_alloc(void) { struct pios_overo_dev * overo_dev; @@ -360,6 +357,15 @@ static void PIOS_OVERO_RegisterTxCallback(uint32_t overo_id, pios_com_callback t overo_dev->tx_out_cb = tx_out_cb; } +#else + +static void PIOS_OVERO_RegisterTxCallback(uint32_t overo_id, pios_com_callback tx_out_cb, uint32_t context) {}; +static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) {}; +static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) {}; +static void PIOS_OVERO_RxStart(uint32_t overo_id, uint16_t rx_bytes_avail) {}; + +#endif /* PIOS_INCLUDE_FREERTOS */ + #endif /** From 3137d5288bd16aad77a82cdd9bdf3223d8699aee Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 19:39:17 -0500 Subject: [PATCH 159/508] Add a message type flag (0x80) to UAVTalk which inserts a timestamp after the previous header and the decoding to read this out. --- flight/UAVTalk/inc/uavtalk.h | 3 +- flight/UAVTalk/inc/uavtalk_priv.h | 7 +++- flight/UAVTalk/uavtalk.c | 68 ++++++++++++++++++++++++++++++- 3 files changed, 74 insertions(+), 4 deletions(-) diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index a45fdb0db..9a2ab6d32 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -45,13 +45,14 @@ typedef struct { typedef void* UAVTalkConnection; -typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState; +typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_TIMESTAMP, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState; // Public functions UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream); int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); +int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId); int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId); diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index 992bf91af..f23adabe4 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -46,13 +46,14 @@ typedef struct { uint16_t size; uint32_t objId; uint16_t instId; + uint16_t timestamp; } uavtalk_max_header; #define UAVTALK_MAX_HEADER_LENGTH sizeof(uavtalk_max_header) typedef uint8_t uavtalk_checksum; #define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum) #define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1) -#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH +#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH #define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH typedef struct { @@ -64,6 +65,7 @@ typedef struct { uint32_t length; uint8_t instanceLength; uint8_t cs; + uint16_t timestamp; int32_t rxCount; UAVTalkRxState state; uint16_t rxPacketLength; @@ -90,11 +92,14 @@ typedef struct { #define UAVTALK_SYNC_VAL 0x3C #define UAVTALK_TYPE_MASK 0xF8 #define UAVTALK_TYPE_VER 0x20 +#define UAVTALK_TIMESTAMPED 0x80 #define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00) #define UAVTALK_TYPE_OBJ_REQ (UAVTALK_TYPE_VER | 0x01) #define UAVTALK_TYPE_OBJ_ACK (UAVTALK_TYPE_VER | 0x02) #define UAVTALK_TYPE_ACK (UAVTALK_TYPE_VER | 0x03) #define UAVTALK_TYPE_NACK (UAVTALK_TYPE_VER | 0x04) +#define UAVTALK_TYPE_OBJ_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ) +#define UAVTALK_TYPE_OBJ_ACK_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ_ACK) //macros #define CHECKCONHANDLE(handle,variable,failcommand) \ diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index bf0d7e100..a24eec9f3 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -189,6 +189,31 @@ int32_t UAVTalkSendObject(UAVTalkConnection connectionHandle, UAVObjHandle obj, } } +/** + * Send the specified object through the telemetry link with a timestamp. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object to send + * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) + * \param[in] timeoutMs Time to wait for the ack, when zero it will return immediately + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + // Send object + if (acked == 1) + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK_TS, timeoutMs); + } + else + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_TS, timeoutMs); + } +} + /** * Execute the requested transaction on an object. * \param[in] connection UAVTalkConnection to be used @@ -388,6 +413,12 @@ UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle { iproc->state = UAVTALK_STATE_INSTID; } + // Check if this is a single instance and has a timestamp in it + else if ((iproc->obj != 0) && (iproc->type & UAVTALK_TIMESTAMPED)) + { + iproc->timestamp = 0; + iproc->state = UAVTALK_STATE_TIMESTAMP; + } else { // If there is a payload get it, otherwise receive checksum @@ -412,14 +443,38 @@ UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle iproc->rxCount = 0; + // If there is a timestamp, get it + if ((iproc->length > 0) && (iproc->type & UAVTALK_TIMESTAMPED)) + { + iproc->timestamp = 0; + iproc->state = UAVTALK_STATE_TIMESTAMP; + } // If there is a payload get it, otherwise receive checksum - if (iproc->length > 0) + else if (iproc->length > 0) iproc->state = UAVTALK_STATE_DATA; else iproc->state = UAVTALK_STATE_CS; break; - + + case UAVTALK_STATE_TIMESTAMP: + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + iproc->timestamp += rxbyte << (8*(iproc->rxCount++)); + + if (iproc->rxCount < 2) + break; + + iproc->rxCount = 0; + + // If there is a payload get it, otherwise receive checksum + if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; + else + iproc->state = UAVTALK_STATE_CS; + break; + case UAVTALK_STATE_DATA: // update the CRC @@ -717,6 +772,15 @@ static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle connection->txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF); dataOffset = 10; } + + // Add timestamp when the transaction type is appropriate + if (type & UAVTALK_TIMESTAMPED) + { + portTickType time = xTaskGetTickCount(); + connection->txBuffer[dataOffset] = (uint8_t)(time & 0xFF); + connection->txBuffer[dataOffset + 1] = (uint8_t)((time >> 8) & 0xFF); + dataOffset += 2; + } // Determine data length if (type == UAVTALK_TYPE_OBJ_REQ || type == UAVTALK_TYPE_ACK) From 13ff0dbb36cedacf7c8e62c5898b3a87c26ba195 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 19:44:07 -0500 Subject: [PATCH 160/508] Add accessor method to get the time of the last timestamp to avoid breaking the API --- flight/UAVTalk/inc/uavtalk.h | 1 + flight/UAVTalk/uavtalk.c | 13 +++++++++++++ 2 files changed, 14 insertions(+) diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index 9a2ab6d32..6223856f2 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -60,6 +60,7 @@ UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t r UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte); void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); void UAVTalkResetStats(UAVTalkConnection connection); +void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp); #endif // UAVTALK_H /** diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index a24eec9f3..d6831d4e1 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -147,6 +147,19 @@ void UAVTalkResetStats(UAVTalkConnection connectionHandle) xSemaphoreGiveRecursive(connection->lock); } +/** + * Accessor method to get the timestamp from the last UAVTalk message + */ +void UAVTalkGetLastTimestamp(UAVTalkConnection connectionHandle, uint16_t *timestamp) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return); + + UAVTalkInputProcessor *iproc = &connection->iproc; + *timestamp = iproc->timestamp; +} + + /** * Request an update for the specified object, on success the object data would have been * updated by the GCS. From 1f7345ef7760820db2d5fab2b7e8ac013060be35 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 19:59:01 -0500 Subject: [PATCH 161/508] Dos2unix uavtalk files --- flight/UAVTalk/inc/uavtalk.h | 138 +-- flight/UAVTalk/inc/uavtalk_priv.h | 230 ++-- flight/UAVTalk/uavtalk.c | 1778 ++++++++++++++--------------- 3 files changed, 1073 insertions(+), 1073 deletions(-) diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index 6223856f2..ab47a1924 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -1,69 +1,69 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file uavtalk.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the UAVTalk library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef UAVTALK_H -#define UAVTALK_H - -// Public types -typedef int32_t (*UAVTalkOutputStream)(uint8_t* data, int32_t length); - -typedef struct { - uint32_t txBytes; - uint32_t rxBytes; - uint32_t txObjectBytes; - uint32_t rxObjectBytes; - uint32_t rxObjects; - uint32_t txObjects; - uint32_t txErrors; - uint32_t rxErrors; -} UAVTalkStats; - -typedef void* UAVTalkConnection; - -typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_TIMESTAMP, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState; - -// Public functions -UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream); -int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); -UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); -int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); -int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); -int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); -int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId); -int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId); -UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); -UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte); -void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); -void UAVTalkResetStats(UAVTalkConnection connection); -void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp); - -#endif // UAVTALK_H -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file uavtalk.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the UAVTalk library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UAVTALK_H +#define UAVTALK_H + +// Public types +typedef int32_t (*UAVTalkOutputStream)(uint8_t* data, int32_t length); + +typedef struct { + uint32_t txBytes; + uint32_t rxBytes; + uint32_t txObjectBytes; + uint32_t rxObjectBytes; + uint32_t rxObjects; + uint32_t txObjects; + uint32_t txErrors; + uint32_t rxErrors; +} UAVTalkStats; + +typedef void* UAVTalkConnection; + +typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_TIMESTAMP, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState; + +// Public functions +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream); +int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); +UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); +int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); +int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); +int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); +int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId); +int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId); +UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); +UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte); +void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); +void UAVTalkResetStats(UAVTalkConnection connection); +void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp); + +#endif // UAVTALK_H +/** + * @} + * @} + */ diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index f23adabe4..5ed872e1e 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file uavtalk.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Private include file of the UAVTalk library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef UAVTALK_PRIV_H -#define UAVTALK_PRIV_H - -#include "uavobjectsinit.h" - -// Private types and constants -typedef struct { - uint8_t sync; - uint8_t type; - uint16_t size; - uint32_t objId; -} uavtalk_min_header; -#define UAVTALK_MIN_HEADER_LENGTH sizeof(uavtalk_min_header) - -typedef struct { - uint8_t sync; - uint8_t type; - uint16_t size; - uint32_t objId; - uint16_t instId; - uint16_t timestamp; -} uavtalk_max_header; -#define UAVTALK_MAX_HEADER_LENGTH sizeof(uavtalk_max_header) - -typedef uint8_t uavtalk_checksum; -#define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum) -#define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1) -#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH -#define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH - -typedef struct { - UAVObjHandle obj; - uint8_t type; - uint16_t packet_size; - uint32_t objId; - uint16_t instId; - uint32_t length; - uint8_t instanceLength; - uint8_t cs; - uint16_t timestamp; - int32_t rxCount; - UAVTalkRxState state; - uint16_t rxPacketLength; -} UAVTalkInputProcessor; - -typedef struct { - uint8_t canari; - UAVTalkOutputStream outStream; - xSemaphoreHandle lock; - xSemaphoreHandle transLock; - xSemaphoreHandle respSema; - UAVObjHandle respObj; - uint16_t respInstId; - UAVTalkStats stats; - UAVTalkInputProcessor iproc; - uint8_t *rxBuffer; - uint32_t txSize; - uint8_t *txBuffer; -} UAVTalkConnectionData; - -#define UAVTALK_CANARI 0xCA -#define UAVTALK_WAITFOREVER -1 -#define UAVTALK_NOWAIT 0 -#define UAVTALK_SYNC_VAL 0x3C -#define UAVTALK_TYPE_MASK 0xF8 -#define UAVTALK_TYPE_VER 0x20 -#define UAVTALK_TIMESTAMPED 0x80 -#define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00) -#define UAVTALK_TYPE_OBJ_REQ (UAVTALK_TYPE_VER | 0x01) -#define UAVTALK_TYPE_OBJ_ACK (UAVTALK_TYPE_VER | 0x02) -#define UAVTALK_TYPE_ACK (UAVTALK_TYPE_VER | 0x03) -#define UAVTALK_TYPE_NACK (UAVTALK_TYPE_VER | 0x04) -#define UAVTALK_TYPE_OBJ_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ) -#define UAVTALK_TYPE_OBJ_ACK_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ_ACK) - -//macros -#define CHECKCONHANDLE(handle,variable,failcommand) \ - variable = (UAVTalkConnectionData*) handle; \ - if (variable == NULL || variable->canari != UAVTALK_CANARI) { \ - failcommand; \ - } - -#endif // UAVTALK__PRIV_H -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file uavtalk.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Private include file of the UAVTalk library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UAVTALK_PRIV_H +#define UAVTALK_PRIV_H + +#include "uavobjectsinit.h" + +// Private types and constants +typedef struct { + uint8_t sync; + uint8_t type; + uint16_t size; + uint32_t objId; +} uavtalk_min_header; +#define UAVTALK_MIN_HEADER_LENGTH sizeof(uavtalk_min_header) + +typedef struct { + uint8_t sync; + uint8_t type; + uint16_t size; + uint32_t objId; + uint16_t instId; + uint16_t timestamp; +} uavtalk_max_header; +#define UAVTALK_MAX_HEADER_LENGTH sizeof(uavtalk_max_header) + +typedef uint8_t uavtalk_checksum; +#define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum) +#define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1) +#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH +#define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH + +typedef struct { + UAVObjHandle obj; + uint8_t type; + uint16_t packet_size; + uint32_t objId; + uint16_t instId; + uint32_t length; + uint8_t instanceLength; + uint8_t cs; + uint16_t timestamp; + int32_t rxCount; + UAVTalkRxState state; + uint16_t rxPacketLength; +} UAVTalkInputProcessor; + +typedef struct { + uint8_t canari; + UAVTalkOutputStream outStream; + xSemaphoreHandle lock; + xSemaphoreHandle transLock; + xSemaphoreHandle respSema; + UAVObjHandle respObj; + uint16_t respInstId; + UAVTalkStats stats; + UAVTalkInputProcessor iproc; + uint8_t *rxBuffer; + uint32_t txSize; + uint8_t *txBuffer; +} UAVTalkConnectionData; + +#define UAVTALK_CANARI 0xCA +#define UAVTALK_WAITFOREVER -1 +#define UAVTALK_NOWAIT 0 +#define UAVTALK_SYNC_VAL 0x3C +#define UAVTALK_TYPE_MASK 0xF8 +#define UAVTALK_TYPE_VER 0x20 +#define UAVTALK_TIMESTAMPED 0x80 +#define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00) +#define UAVTALK_TYPE_OBJ_REQ (UAVTALK_TYPE_VER | 0x01) +#define UAVTALK_TYPE_OBJ_ACK (UAVTALK_TYPE_VER | 0x02) +#define UAVTALK_TYPE_ACK (UAVTALK_TYPE_VER | 0x03) +#define UAVTALK_TYPE_NACK (UAVTALK_TYPE_VER | 0x04) +#define UAVTALK_TYPE_OBJ_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ) +#define UAVTALK_TYPE_OBJ_ACK_TS (UAVTALK_TIMESTAMPED | UAVTALK_TYPE_OBJ_ACK) + +//macros +#define CHECKCONHANDLE(handle,variable,failcommand) \ + variable = (UAVTalkConnectionData*) handle; \ + if (variable == NULL || variable->canari != UAVTALK_CANARI) { \ + failcommand; \ + } + +#endif // UAVTALK__PRIV_H +/** + * @} + * @} + */ diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index d6831d4e1..d3c1c250d 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -1,889 +1,889 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * - * @file uavtalk.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief UAVTalk library, implements to telemetry protocol. See the wiki for more details. - * This library should not be called directly by the application, it is only used by the - * Telemetry module. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "uavtalk_priv.h" - - -// Private functions -static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout); -static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); -static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); -static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId); -static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length); -static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId); - -/** - * Initialize the UAVTalk library - * \param[in] connection UAVTalkConnection to be used - * \param[in] outputStream Function pointer that is called to send a data buffer - * \return 0 Success - * \return -1 Failure - */ -UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream) -{ - // allocate object - UAVTalkConnectionData * connection = pvPortMalloc(sizeof(UAVTalkConnectionData)); - if (!connection) return 0; - connection->canari = UAVTALK_CANARI; - connection->iproc.rxPacketLength = 0; - connection->iproc.state = UAVTALK_STATE_SYNC; - connection->outStream = outputStream; - connection->lock = xSemaphoreCreateRecursiveMutex(); - connection->transLock = xSemaphoreCreateRecursiveMutex(); - // allocate buffers - connection->rxBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); - if (!connection->rxBuffer) return 0; - connection->txBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); - if (!connection->txBuffer) return 0; - vSemaphoreCreateBinary(connection->respSema); - xSemaphoreTake(connection->respSema, 0); // reset to zero - UAVTalkResetStats( (UAVTalkConnection) connection ); - return (UAVTalkConnection) connection; -} - -/** - * Set the communication output stream - * \param[in] connection UAVTalkConnection to be used - * \param[in] outputStream Function pointer that is called to send a data buffer - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSetOutputStream(UAVTalkConnection connectionHandle, UAVTalkOutputStream outputStream) -{ - - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - - // Lock - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - - // set output stream - connection->outStream = outputStream; - - // Release lock - xSemaphoreGiveRecursive(connection->lock); - - return 0; - -} - -/** - * Get current output stream - * \param[in] connection UAVTalkConnection to be used - * @return UAVTarlkOutputStream the output stream used - */ -UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connectionHandle) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return NULL); - return connection->outStream; -} - -/** - * Get communication statistics counters - * \param[in] connection UAVTalkConnection to be used - * @param[out] statsOut Statistics counters - */ -void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats* statsOut) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return ); - - // Lock - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - - // Copy stats - memcpy(statsOut, &connection->stats, sizeof(UAVTalkStats)); - - // Release lock - xSemaphoreGiveRecursive(connection->lock); -} - -/** - * Reset the statistics counters. - * \param[in] connection UAVTalkConnection to be used - */ -void UAVTalkResetStats(UAVTalkConnection connectionHandle) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return); - - // Lock - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - - // Clear stats - memset(&connection->stats, 0, sizeof(UAVTalkStats)); - - // Release lock - xSemaphoreGiveRecursive(connection->lock); -} - -/** - * Accessor method to get the timestamp from the last UAVTalk message - */ -void UAVTalkGetLastTimestamp(UAVTalkConnection connectionHandle, uint16_t *timestamp) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return); - - UAVTalkInputProcessor *iproc = &connection->iproc; - *timestamp = iproc->timestamp; -} - - -/** - * Request an update for the specified object, on success the object data would have been - * updated by the GCS. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object to update - * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] timeout Time to wait for the response, when zero it will return immediately - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSendObjectRequest(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, int32_t timeout) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ, timeout); -} - -/** - * Send the specified object through the telemetry link. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object to send - * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) - * \param[in] timeoutMs Time to wait for the ack, when zero it will return immediately - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSendObject(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - // Send object - if (acked == 1) - { - return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK, timeoutMs); - } - else - { - return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ, timeoutMs); - } -} - -/** - * Send the specified object through the telemetry link with a timestamp. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object to send - * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) - * \param[in] timeoutMs Time to wait for the ack, when zero it will return immediately - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - // Send object - if (acked == 1) - { - return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK_TS, timeoutMs); - } - else - { - return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_TS, timeoutMs); - } -} - -/** - * Execute the requested transaction on an object. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] type Transaction type - * UAVTALK_TYPE_OBJ: send object, - * UAVTALK_TYPE_OBJ_REQ: request object update - * UAVTALK_TYPE_OBJ_ACK: send object with an ack - * \return 0 Success - * \return -1 Failure - */ -static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs) -{ - int32_t respReceived; - - // Send object depending on if a response is needed - if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_REQ) - { - // Get transaction lock (will block if a transaction is pending) - xSemaphoreTakeRecursive(connection->transLock, portMAX_DELAY); - // Send object - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - connection->respObj = obj; - connection->respInstId = instId; - sendObject(connection, obj, instId, type); - xSemaphoreGiveRecursive(connection->lock); - // Wait for response (or timeout) - respReceived = xSemaphoreTake(connection->respSema, timeoutMs/portTICK_RATE_MS); - // Check if a response was received - if (respReceived == pdFALSE) - { - // Cancel transaction - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - xSemaphoreTake(connection->respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema) - connection->respObj = 0; - xSemaphoreGiveRecursive(connection->lock); - xSemaphoreGiveRecursive(connection->transLock); - return -1; - } - else - { - xSemaphoreGiveRecursive(connection->transLock); - return 0; - } - } - else if (type == UAVTALK_TYPE_OBJ) - { - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); - xSemaphoreGiveRecursive(connection->lock); - return 0; - } - else - { - return -1; - } -} - -/** - * Process an byte from the telemetry stream. - * \param[in] connection UAVTalkConnection to be used - * \param[in] rxbyte Received byte - * \return UAVTalkRxState - */ -UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle, uint8_t rxbyte) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - - UAVTalkInputProcessor *iproc = &connection->iproc; - ++connection->stats.rxBytes; - - if (iproc->state == UAVTALK_STATE_ERROR || iproc->state == UAVTALK_STATE_COMPLETE) - iproc->state = UAVTALK_STATE_SYNC; - - if (iproc->rxPacketLength < 0xffff) - iproc->rxPacketLength++; // update packet byte count - - // Receive state machine - switch (iproc->state) - { - case UAVTALK_STATE_SYNC: - if (rxbyte != UAVTALK_SYNC_VAL) - break; - - // Initialize and update the CRC - iproc->cs = PIOS_CRC_updateByte(0, rxbyte); - - iproc->rxPacketLength = 1; - - iproc->state = UAVTALK_STATE_TYPE; - break; - - case UAVTALK_STATE_TYPE: - - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER) - { - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - iproc->type = rxbyte; - - iproc->packet_size = 0; - - iproc->state = UAVTALK_STATE_SIZE; - iproc->rxCount = 0; - break; - - case UAVTALK_STATE_SIZE: - - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - if (iproc->rxCount == 0) - { - iproc->packet_size += rxbyte; - iproc->rxCount++; - break; - } - - iproc->packet_size += rxbyte << 8; - - if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH) - { // incorrect packet size - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - iproc->rxCount = 0; - iproc->objId = 0; - iproc->state = UAVTALK_STATE_OBJID; - break; - - case UAVTALK_STATE_OBJID: - - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - iproc->objId += rxbyte << (8*(iproc->rxCount++)); - - if (iproc->rxCount < 4) - break; - - // Search for object. - iproc->obj = UAVObjGetByID(iproc->objId); - - // Determine data length - if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK) - { - iproc->length = 0; - iproc->instanceLength = 0; - } - else - { - if (iproc->obj) - { - iproc->length = UAVObjGetNumBytes(iproc->obj); - iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); - } - else - { - // We don't know if it's a multi-instance object, so just assume it's 0. - iproc->instanceLength = 0; - iproc->length = iproc->packet_size - iproc->rxPacketLength; - } - } - - // Check length and determine next state - if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH) - { - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - // Check the lengths match - if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size) - { // packet error - mismatched packet size - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - iproc->instId = 0; - if (iproc->type == UAVTALK_TYPE_NACK) - { - // If this is a NACK, we skip to Checksum - iproc->state = UAVTALK_STATE_CS; - } - // Check if this is a single instance object (i.e. if the instance ID field is coming next) - else if ((iproc->obj != 0) && !UAVObjIsSingleInstance(iproc->obj)) - { - iproc->state = UAVTALK_STATE_INSTID; - } - // Check if this is a single instance and has a timestamp in it - else if ((iproc->obj != 0) && (iproc->type & UAVTALK_TIMESTAMPED)) - { - iproc->timestamp = 0; - iproc->state = UAVTALK_STATE_TIMESTAMP; - } - else - { - // If there is a payload get it, otherwise receive checksum - if (iproc->length > 0) - iproc->state = UAVTALK_STATE_DATA; - else - iproc->state = UAVTALK_STATE_CS; - } - iproc->rxCount = 0; - - break; - - case UAVTALK_STATE_INSTID: - - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - iproc->instId += rxbyte << (8*(iproc->rxCount++)); - - if (iproc->rxCount < 2) - break; - - iproc->rxCount = 0; - - // If there is a timestamp, get it - if ((iproc->length > 0) && (iproc->type & UAVTALK_TIMESTAMPED)) - { - iproc->timestamp = 0; - iproc->state = UAVTALK_STATE_TIMESTAMP; - } - // If there is a payload get it, otherwise receive checksum - else if (iproc->length > 0) - iproc->state = UAVTALK_STATE_DATA; - else - iproc->state = UAVTALK_STATE_CS; - - break; - - case UAVTALK_STATE_TIMESTAMP: - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - iproc->timestamp += rxbyte << (8*(iproc->rxCount++)); - - if (iproc->rxCount < 2) - break; - - iproc->rxCount = 0; - - // If there is a payload get it, otherwise receive checksum - if (iproc->length > 0) - iproc->state = UAVTALK_STATE_DATA; - else - iproc->state = UAVTALK_STATE_CS; - break; - - case UAVTALK_STATE_DATA: - - // update the CRC - iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - - connection->rxBuffer[iproc->rxCount++] = rxbyte; - if (iproc->rxCount < iproc->length) - break; - - iproc->state = UAVTALK_STATE_CS; - iproc->rxCount = 0; - break; - - case UAVTALK_STATE_CS: - - // the CRC byte - if (rxbyte != iproc->cs) - { // packet error - faulty CRC - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - if (iproc->rxPacketLength != (iproc->packet_size + 1)) - { // packet error - mismatched packet size - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_ERROR; - break; - } - - connection->stats.rxObjectBytes += iproc->length; - connection->stats.rxObjects++; - - iproc->state = UAVTALK_STATE_COMPLETE; - break; - - default: - connection->stats.rxErrors++; - iproc->state = UAVTALK_STATE_ERROR; - } - - // Done - return iproc->state; -} - -/** - * Process an byte from the telemetry stream. - * \param[in] connection UAVTalkConnection to be used - * \param[in] rxbyte Received byte - * \return UAVTalkRxState - */ -UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) -{ - UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte); - - if (state == UAVTALK_STATE_COMPLETE) - { - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - UAVTalkInputProcessor *iproc = &connection->iproc; - - xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length); - xSemaphoreGiveRecursive(connection->lock); - } - - return state; -} - -/** - * Send a ACK through the telemetry link. - * \param[in] connectionHandle UAVTalkConnection to be used - * \param[in] objId Object ID to send a NACK for - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - - return sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); -} - -/** - * Send a NACK through the telemetry link. - * \param[in] connectionHandle UAVTalkConnection to be used - * \param[in] objId Object ID to send a NACK for - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId) -{ - UAVTalkConnectionData *connection; - CHECKCONHANDLE(connectionHandle,connection,return -1); - - return sendNack(connection, objId); -} - -/** - * Receive an object. This function process objects received through the telemetry stream. - * \param[in] connection UAVTalkConnection to be used - * \param[in] type Type of received message (UAVTALK_TYPE_OBJ, UAVTALK_TYPE_OBJ_REQ, UAVTALK_TYPE_OBJ_ACK, UAVTALK_TYPE_ACK, UAVTALK_TYPE_NACK) - * \param[in] objId ID of the object to work on - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] data Data buffer - * \param[in] length Buffer length - * \return 0 Success - * \return -1 Failure - */ -static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length) -{ - UAVObjHandle obj; - int32_t ret = 0; - - // Get the handle to the Object. Will be zero - // if object does not exist. - obj = UAVObjGetByID(objId); - - // Process message type - switch (type) { - case UAVTALK_TYPE_OBJ: - // All instances, not allowed for OBJ messages - if (obj && (instId != UAVOBJ_ALL_INSTANCES)) - { - // Unpack object, if the instance does not exist it will be created! - UAVObjUnpack(obj, instId, data); - // Check if an ack is pending - updateAck(connection, obj, instId); - } - else - { - ret = -1; - } - break; - case UAVTALK_TYPE_OBJ_ACK: - // All instances, not allowed for OBJ_ACK messages - if (obj && (instId != UAVOBJ_ALL_INSTANCES)) - { - // Unpack object, if the instance does not exist it will be created! - if ( UAVObjUnpack(obj, instId, data) == 0 ) - { - // Transmit ACK - sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); - } - else - { - ret = -1; - } - } - else - { - ret = -1; - } - break; - case UAVTALK_TYPE_OBJ_REQ: - // Send requested object if message is of type OBJ_REQ - if (obj == 0) - sendNack(connection, objId); - else - sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); - break; - case UAVTALK_TYPE_NACK: - // Do nothing on flight side, let it time out. - break; - case UAVTALK_TYPE_ACK: - // All instances, not allowed for ACK messages - if (obj && (instId != UAVOBJ_ALL_INSTANCES)) - { - // Check if an ack is pending - updateAck(connection, obj, instId); - } - else - { - ret = -1; - } - break; - default: - ret = -1; - } - // Done - return ret; -} - -/** - * Check if an ack is pending on an object and give response semaphore - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - */ -static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId) -{ - if (connection->respObj == obj && (connection->respInstId == instId || connection->respInstId == UAVOBJ_ALL_INSTANCES)) - { - xSemaphoreGive(connection->respSema); - connection->respObj = 0; - } -} - -/** - * Send an object through the telemetry link. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object handle to send - * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances - * \param[in] type Transaction type - * \return 0 Success - * \return -1 Failure - */ -static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) -{ - uint32_t numInst; - uint32_t n; - - // If all instances are requested and this is a single instance object, force instance ID to zero - if ( instId == UAVOBJ_ALL_INSTANCES && UAVObjIsSingleInstance(obj) ) - { - instId = 0; - } - - // Process message type - if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_ACK ) - { - if (instId == UAVOBJ_ALL_INSTANCES) - { - // Get number of instances - numInst = UAVObjGetNumInstances(obj); - // Send all instances - for (n = 0; n < numInst; ++n) - { - sendSingleObject(connection, obj, n, type); - } - return 0; - } - else - { - return sendSingleObject(connection, obj, instId, type); - } - } - else if (type == UAVTALK_TYPE_OBJ_REQ) - { - return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ); - } - else if (type == UAVTALK_TYPE_ACK) - { - if ( instId != UAVOBJ_ALL_INSTANCES ) - { - return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_ACK); - } - else - { - return -1; - } - } - else - { - return -1; - } -} - -/** - * Send an object through the telemetry link. - * \param[in] connection UAVTalkConnection to be used - * \param[in] obj Object handle to send - * \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use sendObject() instead) - * \param[in] type Transaction type - * \return 0 Success - * \return -1 Failure - */ -static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) -{ - int32_t length; - int32_t dataOffset; - uint32_t objId; - - if (!connection->outStream) return -1; - - // Setup type and object id fields - objId = UAVObjGetID(obj); - connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte - connection->txBuffer[1] = type; - // data length inserted here below - connection->txBuffer[4] = (uint8_t)(objId & 0xFF); - connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); - connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); - connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); - - // Setup instance ID if one is required - if (UAVObjIsSingleInstance(obj)) - { - dataOffset = 8; - } - else - { - connection->txBuffer[8] = (uint8_t)(instId & 0xFF); - connection->txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF); - dataOffset = 10; - } - - // Add timestamp when the transaction type is appropriate - if (type & UAVTALK_TIMESTAMPED) - { - portTickType time = xTaskGetTickCount(); - connection->txBuffer[dataOffset] = (uint8_t)(time & 0xFF); - connection->txBuffer[dataOffset + 1] = (uint8_t)((time >> 8) & 0xFF); - dataOffset += 2; - } - - // Determine data length - if (type == UAVTALK_TYPE_OBJ_REQ || type == UAVTALK_TYPE_ACK) - { - length = 0; - } - else - { - length = UAVObjGetNumBytes(obj); - } - - // Check length - if (length >= UAVTALK_MAX_PAYLOAD_LENGTH) - { - return -1; - } - - // Copy data (if any) - if (length > 0) - { - if ( UAVObjPack(obj, instId, &connection->txBuffer[dataOffset]) < 0 ) - { - return -1; - } - } - - // Store the packet length - connection->txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF); - connection->txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF); - - // Calculate checksum - connection->txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset+length); - - uint16_t tx_msg_len = dataOffset+length+UAVTALK_CHECKSUM_LENGTH; - int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); - - if (rc == tx_msg_len) { - // Update stats - ++connection->stats.txObjects; - connection->stats.txBytes += tx_msg_len; - connection->stats.txObjectBytes += length; - } - - // Done - return 0; -} - -/** - * Send a NACK through the telemetry link. - * \param[in] connection UAVTalkConnection to be used - * \param[in] objId Object ID to send a NACK for - * \return 0 Success - * \return -1 Failure - */ -static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId) -{ - int32_t dataOffset; - - if (!connection->outStream) return -1; - - connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte - connection->txBuffer[1] = UAVTALK_TYPE_NACK; - // data length inserted here below - connection->txBuffer[4] = (uint8_t)(objId & 0xFF); - connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); - connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); - connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); - - dataOffset = 8; - - // Store the packet length - connection->txBuffer[2] = (uint8_t)((dataOffset) & 0xFF); - connection->txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF); - - // Calculate checksum - connection->txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset); - - uint16_t tx_msg_len = dataOffset+UAVTALK_CHECKSUM_LENGTH; - int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); - - if (rc == tx_msg_len) { - // Update stats - connection->stats.txBytes += tx_msg_len; - } - - // Done - return 0; -} - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * + * @file uavtalk.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief UAVTalk library, implements to telemetry protocol. See the wiki for more details. + * This library should not be called directly by the application, it is only used by the + * Telemetry module. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "uavtalk_priv.h" + + +// Private functions +static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout); +static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); +static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); +static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId); +static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length); +static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId); + +/** + * Initialize the UAVTalk library + * \param[in] connection UAVTalkConnection to be used + * \param[in] outputStream Function pointer that is called to send a data buffer + * \return 0 Success + * \return -1 Failure + */ +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream) +{ + // allocate object + UAVTalkConnectionData * connection = pvPortMalloc(sizeof(UAVTalkConnectionData)); + if (!connection) return 0; + connection->canari = UAVTALK_CANARI; + connection->iproc.rxPacketLength = 0; + connection->iproc.state = UAVTALK_STATE_SYNC; + connection->outStream = outputStream; + connection->lock = xSemaphoreCreateRecursiveMutex(); + connection->transLock = xSemaphoreCreateRecursiveMutex(); + // allocate buffers + connection->rxBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); + if (!connection->rxBuffer) return 0; + connection->txBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); + if (!connection->txBuffer) return 0; + vSemaphoreCreateBinary(connection->respSema); + xSemaphoreTake(connection->respSema, 0); // reset to zero + UAVTalkResetStats( (UAVTalkConnection) connection ); + return (UAVTalkConnection) connection; +} + +/** + * Set the communication output stream + * \param[in] connection UAVTalkConnection to be used + * \param[in] outputStream Function pointer that is called to send a data buffer + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSetOutputStream(UAVTalkConnection connectionHandle, UAVTalkOutputStream outputStream) +{ + + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + // set output stream + connection->outStream = outputStream; + + // Release lock + xSemaphoreGiveRecursive(connection->lock); + + return 0; + +} + +/** + * Get current output stream + * \param[in] connection UAVTalkConnection to be used + * @return UAVTarlkOutputStream the output stream used + */ +UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connectionHandle) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return NULL); + return connection->outStream; +} + +/** + * Get communication statistics counters + * \param[in] connection UAVTalkConnection to be used + * @param[out] statsOut Statistics counters + */ +void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats* statsOut) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return ); + + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + // Copy stats + memcpy(statsOut, &connection->stats, sizeof(UAVTalkStats)); + + // Release lock + xSemaphoreGiveRecursive(connection->lock); +} + +/** + * Reset the statistics counters. + * \param[in] connection UAVTalkConnection to be used + */ +void UAVTalkResetStats(UAVTalkConnection connectionHandle) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return); + + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + // Clear stats + memset(&connection->stats, 0, sizeof(UAVTalkStats)); + + // Release lock + xSemaphoreGiveRecursive(connection->lock); +} + +/** + * Accessor method to get the timestamp from the last UAVTalk message + */ +void UAVTalkGetLastTimestamp(UAVTalkConnection connectionHandle, uint16_t *timestamp) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return); + + UAVTalkInputProcessor *iproc = &connection->iproc; + *timestamp = iproc->timestamp; +} + + +/** + * Request an update for the specified object, on success the object data would have been + * updated by the GCS. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object to update + * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] timeout Time to wait for the response, when zero it will return immediately + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendObjectRequest(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, int32_t timeout) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ, timeout); +} + +/** + * Send the specified object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object to send + * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) + * \param[in] timeoutMs Time to wait for the ack, when zero it will return immediately + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendObject(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + // Send object + if (acked == 1) + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK, timeoutMs); + } + else + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ, timeoutMs); + } +} + +/** + * Send the specified object through the telemetry link with a timestamp. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object to send + * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) + * \param[in] timeoutMs Time to wait for the ack, when zero it will return immediately + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + // Send object + if (acked == 1) + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK_TS, timeoutMs); + } + else + { + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_TS, timeoutMs); + } +} + +/** + * Execute the requested transaction on an object. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] type Transaction type + * UAVTALK_TYPE_OBJ: send object, + * UAVTALK_TYPE_OBJ_REQ: request object update + * UAVTALK_TYPE_OBJ_ACK: send object with an ack + * \return 0 Success + * \return -1 Failure + */ +static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs) +{ + int32_t respReceived; + + // Send object depending on if a response is needed + if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_REQ) + { + // Get transaction lock (will block if a transaction is pending) + xSemaphoreTakeRecursive(connection->transLock, portMAX_DELAY); + // Send object + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + connection->respObj = obj; + connection->respInstId = instId; + sendObject(connection, obj, instId, type); + xSemaphoreGiveRecursive(connection->lock); + // Wait for response (or timeout) + respReceived = xSemaphoreTake(connection->respSema, timeoutMs/portTICK_RATE_MS); + // Check if a response was received + if (respReceived == pdFALSE) + { + // Cancel transaction + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + xSemaphoreTake(connection->respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema) + connection->respObj = 0; + xSemaphoreGiveRecursive(connection->lock); + xSemaphoreGiveRecursive(connection->transLock); + return -1; + } + else + { + xSemaphoreGiveRecursive(connection->transLock); + return 0; + } + } + else if (type == UAVTALK_TYPE_OBJ) + { + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); + xSemaphoreGiveRecursive(connection->lock); + return 0; + } + else + { + return -1; + } +} + +/** + * Process an byte from the telemetry stream. + * \param[in] connection UAVTalkConnection to be used + * \param[in] rxbyte Received byte + * \return UAVTalkRxState + */ +UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle, uint8_t rxbyte) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + UAVTalkInputProcessor *iproc = &connection->iproc; + ++connection->stats.rxBytes; + + if (iproc->state == UAVTALK_STATE_ERROR || iproc->state == UAVTALK_STATE_COMPLETE) + iproc->state = UAVTALK_STATE_SYNC; + + if (iproc->rxPacketLength < 0xffff) + iproc->rxPacketLength++; // update packet byte count + + // Receive state machine + switch (iproc->state) + { + case UAVTALK_STATE_SYNC: + if (rxbyte != UAVTALK_SYNC_VAL) + break; + + // Initialize and update the CRC + iproc->cs = PIOS_CRC_updateByte(0, rxbyte); + + iproc->rxPacketLength = 1; + + iproc->state = UAVTALK_STATE_TYPE; + break; + + case UAVTALK_STATE_TYPE: + + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER) + { + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + iproc->type = rxbyte; + + iproc->packet_size = 0; + + iproc->state = UAVTALK_STATE_SIZE; + iproc->rxCount = 0; + break; + + case UAVTALK_STATE_SIZE: + + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + if (iproc->rxCount == 0) + { + iproc->packet_size += rxbyte; + iproc->rxCount++; + break; + } + + iproc->packet_size += rxbyte << 8; + + if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH) + { // incorrect packet size + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + iproc->rxCount = 0; + iproc->objId = 0; + iproc->state = UAVTALK_STATE_OBJID; + break; + + case UAVTALK_STATE_OBJID: + + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + iproc->objId += rxbyte << (8*(iproc->rxCount++)); + + if (iproc->rxCount < 4) + break; + + // Search for object. + iproc->obj = UAVObjGetByID(iproc->objId); + + // Determine data length + if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK) + { + iproc->length = 0; + iproc->instanceLength = 0; + } + else + { + if (iproc->obj) + { + iproc->length = UAVObjGetNumBytes(iproc->obj); + iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); + } + else + { + // We don't know if it's a multi-instance object, so just assume it's 0. + iproc->instanceLength = 0; + iproc->length = iproc->packet_size - iproc->rxPacketLength; + } + } + + // Check length and determine next state + if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH) + { + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + // Check the lengths match + if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size) + { // packet error - mismatched packet size + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + iproc->instId = 0; + if (iproc->type == UAVTALK_TYPE_NACK) + { + // If this is a NACK, we skip to Checksum + iproc->state = UAVTALK_STATE_CS; + } + // Check if this is a single instance object (i.e. if the instance ID field is coming next) + else if ((iproc->obj != 0) && !UAVObjIsSingleInstance(iproc->obj)) + { + iproc->state = UAVTALK_STATE_INSTID; + } + // Check if this is a single instance and has a timestamp in it + else if ((iproc->obj != 0) && (iproc->type & UAVTALK_TIMESTAMPED)) + { + iproc->timestamp = 0; + iproc->state = UAVTALK_STATE_TIMESTAMP; + } + else + { + // If there is a payload get it, otherwise receive checksum + if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; + else + iproc->state = UAVTALK_STATE_CS; + } + iproc->rxCount = 0; + + break; + + case UAVTALK_STATE_INSTID: + + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + iproc->instId += rxbyte << (8*(iproc->rxCount++)); + + if (iproc->rxCount < 2) + break; + + iproc->rxCount = 0; + + // If there is a timestamp, get it + if ((iproc->length > 0) && (iproc->type & UAVTALK_TIMESTAMPED)) + { + iproc->timestamp = 0; + iproc->state = UAVTALK_STATE_TIMESTAMP; + } + // If there is a payload get it, otherwise receive checksum + else if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; + else + iproc->state = UAVTALK_STATE_CS; + + break; + + case UAVTALK_STATE_TIMESTAMP: + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + iproc->timestamp += rxbyte << (8*(iproc->rxCount++)); + + if (iproc->rxCount < 2) + break; + + iproc->rxCount = 0; + + // If there is a payload get it, otherwise receive checksum + if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; + else + iproc->state = UAVTALK_STATE_CS; + break; + + case UAVTALK_STATE_DATA: + + // update the CRC + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); + + connection->rxBuffer[iproc->rxCount++] = rxbyte; + if (iproc->rxCount < iproc->length) + break; + + iproc->state = UAVTALK_STATE_CS; + iproc->rxCount = 0; + break; + + case UAVTALK_STATE_CS: + + // the CRC byte + if (rxbyte != iproc->cs) + { // packet error - faulty CRC + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + if (iproc->rxPacketLength != (iproc->packet_size + 1)) + { // packet error - mismatched packet size + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_ERROR; + break; + } + + connection->stats.rxObjectBytes += iproc->length; + connection->stats.rxObjects++; + + iproc->state = UAVTALK_STATE_COMPLETE; + break; + + default: + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_ERROR; + } + + // Done + return iproc->state; +} + +/** + * Process an byte from the telemetry stream. + * \param[in] connection UAVTalkConnection to be used + * \param[in] rxbyte Received byte + * \return UAVTalkRxState + */ +UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) +{ + UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte); + + if (state == UAVTALK_STATE_COMPLETE) + { + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + UAVTalkInputProcessor *iproc = &connection->iproc; + + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length); + xSemaphoreGiveRecursive(connection->lock); + } + + return state; +} + +/** + * Send a ACK through the telemetry link. + * \param[in] connectionHandle UAVTalkConnection to be used + * \param[in] objId Object ID to send a NACK for + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + return sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); +} + +/** + * Send a NACK through the telemetry link. + * \param[in] connectionHandle UAVTalkConnection to be used + * \param[in] objId Object ID to send a NACK for + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + return sendNack(connection, objId); +} + +/** + * Receive an object. This function process objects received through the telemetry stream. + * \param[in] connection UAVTalkConnection to be used + * \param[in] type Type of received message (UAVTALK_TYPE_OBJ, UAVTALK_TYPE_OBJ_REQ, UAVTALK_TYPE_OBJ_ACK, UAVTALK_TYPE_ACK, UAVTALK_TYPE_NACK) + * \param[in] objId ID of the object to work on + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] data Data buffer + * \param[in] length Buffer length + * \return 0 Success + * \return -1 Failure + */ +static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length) +{ + UAVObjHandle obj; + int32_t ret = 0; + + // Get the handle to the Object. Will be zero + // if object does not exist. + obj = UAVObjGetByID(objId); + + // Process message type + switch (type) { + case UAVTALK_TYPE_OBJ: + // All instances, not allowed for OBJ messages + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) + { + // Unpack object, if the instance does not exist it will be created! + UAVObjUnpack(obj, instId, data); + // Check if an ack is pending + updateAck(connection, obj, instId); + } + else + { + ret = -1; + } + break; + case UAVTALK_TYPE_OBJ_ACK: + // All instances, not allowed for OBJ_ACK messages + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) + { + // Unpack object, if the instance does not exist it will be created! + if ( UAVObjUnpack(obj, instId, data) == 0 ) + { + // Transmit ACK + sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); + } + else + { + ret = -1; + } + } + else + { + ret = -1; + } + break; + case UAVTALK_TYPE_OBJ_REQ: + // Send requested object if message is of type OBJ_REQ + if (obj == 0) + sendNack(connection, objId); + else + sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); + break; + case UAVTALK_TYPE_NACK: + // Do nothing on flight side, let it time out. + break; + case UAVTALK_TYPE_ACK: + // All instances, not allowed for ACK messages + if (obj && (instId != UAVOBJ_ALL_INSTANCES)) + { + // Check if an ack is pending + updateAck(connection, obj, instId); + } + else + { + ret = -1; + } + break; + default: + ret = -1; + } + // Done + return ret; +} + +/** + * Check if an ack is pending on an object and give response semaphore + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + */ +static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId) +{ + if (connection->respObj == obj && (connection->respInstId == instId || connection->respInstId == UAVOBJ_ALL_INSTANCES)) + { + xSemaphoreGive(connection->respSema); + connection->respObj = 0; + } +} + +/** + * Send an object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object handle to send + * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances + * \param[in] type Transaction type + * \return 0 Success + * \return -1 Failure + */ +static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) +{ + uint32_t numInst; + uint32_t n; + + // If all instances are requested and this is a single instance object, force instance ID to zero + if ( instId == UAVOBJ_ALL_INSTANCES && UAVObjIsSingleInstance(obj) ) + { + instId = 0; + } + + // Process message type + if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_ACK ) + { + if (instId == UAVOBJ_ALL_INSTANCES) + { + // Get number of instances + numInst = UAVObjGetNumInstances(obj); + // Send all instances + for (n = 0; n < numInst; ++n) + { + sendSingleObject(connection, obj, n, type); + } + return 0; + } + else + { + return sendSingleObject(connection, obj, instId, type); + } + } + else if (type == UAVTALK_TYPE_OBJ_REQ) + { + return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ); + } + else if (type == UAVTALK_TYPE_ACK) + { + if ( instId != UAVOBJ_ALL_INSTANCES ) + { + return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_ACK); + } + else + { + return -1; + } + } + else + { + return -1; + } +} + +/** + * Send an object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object handle to send + * \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use sendObject() instead) + * \param[in] type Transaction type + * \return 0 Success + * \return -1 Failure + */ +static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) +{ + int32_t length; + int32_t dataOffset; + uint32_t objId; + + if (!connection->outStream) return -1; + + // Setup type and object id fields + objId = UAVObjGetID(obj); + connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte + connection->txBuffer[1] = type; + // data length inserted here below + connection->txBuffer[4] = (uint8_t)(objId & 0xFF); + connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); + connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); + connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); + + // Setup instance ID if one is required + if (UAVObjIsSingleInstance(obj)) + { + dataOffset = 8; + } + else + { + connection->txBuffer[8] = (uint8_t)(instId & 0xFF); + connection->txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF); + dataOffset = 10; + } + + // Add timestamp when the transaction type is appropriate + if (type & UAVTALK_TIMESTAMPED) + { + portTickType time = xTaskGetTickCount(); + connection->txBuffer[dataOffset] = (uint8_t)(time & 0xFF); + connection->txBuffer[dataOffset + 1] = (uint8_t)((time >> 8) & 0xFF); + dataOffset += 2; + } + + // Determine data length + if (type == UAVTALK_TYPE_OBJ_REQ || type == UAVTALK_TYPE_ACK) + { + length = 0; + } + else + { + length = UAVObjGetNumBytes(obj); + } + + // Check length + if (length >= UAVTALK_MAX_PAYLOAD_LENGTH) + { + return -1; + } + + // Copy data (if any) + if (length > 0) + { + if ( UAVObjPack(obj, instId, &connection->txBuffer[dataOffset]) < 0 ) + { + return -1; + } + } + + // Store the packet length + connection->txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF); + connection->txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF); + + // Calculate checksum + connection->txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset+length); + + uint16_t tx_msg_len = dataOffset+length+UAVTALK_CHECKSUM_LENGTH; + int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); + + if (rc == tx_msg_len) { + // Update stats + ++connection->stats.txObjects; + connection->stats.txBytes += tx_msg_len; + connection->stats.txObjectBytes += length; + } + + // Done + return 0; +} + +/** + * Send a NACK through the telemetry link. + * \param[in] connection UAVTalkConnection to be used + * \param[in] objId Object ID to send a NACK for + * \return 0 Success + * \return -1 Failure + */ +static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId) +{ + int32_t dataOffset; + + if (!connection->outStream) return -1; + + connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte + connection->txBuffer[1] = UAVTALK_TYPE_NACK; + // data length inserted here below + connection->txBuffer[4] = (uint8_t)(objId & 0xFF); + connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); + connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); + connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); + + dataOffset = 8; + + // Store the packet length + connection->txBuffer[2] = (uint8_t)((dataOffset) & 0xFF); + connection->txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF); + + // Calculate checksum + connection->txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset); + + uint16_t tx_msg_len = dataOffset+UAVTALK_CHECKSUM_LENGTH; + int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); + + if (rc == tx_msg_len) { + // Update stats + connection->stats.txBytes += tx_msg_len; + } + + // Done + return 0; +} + +/** + * @} + * @} + */ From 617de9c68b1697f559ced9e092c15349daa80f7b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 01:49:53 -0500 Subject: [PATCH 162/508] Revert "Disable the FLASH_FREERTOS flag for revolution so that it doesn't try and use" This reverts commit 7522bd07ba2f8eff8175924110a444104252d036. --- flight/Revolution/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index a84772031..4bb7be2a7 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -66,7 +66,7 @@ #define PIOS_INCLUDE_ETASV3 //#define PIOS_INCLUDE_HCSR04 #define PIOS_FLASH_ON_ACCEL /* true for second revo */ - +#define FLASH_FREERTOS /* Com systems to include */ #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_COM_TELEM From 858c2cd51293fad207c9efd7f82daa10f43264d3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 01:54:04 -0500 Subject: [PATCH 163/508] Increase the size of the overo queue --- flight/Modules/OveroSync/overosync.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index e0554dadc..a56305ce2 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -38,7 +38,7 @@ // Private constants #define OVEROSYNC_PACKET_SIZE 1024 -#define MAX_QUEUE_SIZE 40 +#define MAX_QUEUE_SIZE 60 #define STACK_SIZE_BYTES 512 #define TASK_PRIORITY (tskIDLE_PRIORITY + 0) From ea5c3be0266a514919b6b08aa5a8ab5341bec11e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 02:41:39 -0500 Subject: [PATCH 164/508] Need to add hooks in sendObject and receiveObject to actually transmit _TS objects --- flight/Modules/OveroSync/overosync.c | 8 ++------ flight/UAVTalk/uavtalk.c | 12 ++++++------ 2 files changed, 8 insertions(+), 12 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index a56305ce2..9e5bb8298 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -179,7 +179,7 @@ static void overoSyncTask(void *parameters) if (xQueueReceive(queue, &ev, portMAX_DELAY) == pdTRUE) { // Process event. This calls transmitData - UAVTalkSendObject(uavTalkCon, ev.obj, ev.instId, false, 0); + UAVTalkSendObjectTimestamped(uavTalkCon, ev.obj, ev.instId, false, 0); updateTime = xTaskGetTickCount(); if(((portTickType) (updateTime - lastUpdateTime)) > 1000) { @@ -209,14 +209,10 @@ static void overoSyncTask(void *parameters) */ static int32_t packData(uint8_t * data, int32_t length) { - portTickType tickTime = xTaskGetTickCount(); - - if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, (uint8_t *) &tickTime, sizeof(tickTime)) < 0) - goto fail; if( PIOS_COM_SendBufferNonBlocking(pios_com_overo_id, data, length) < 0) goto fail; - overosync->sent_bytes += length + 4; + overosync->sent_bytes += length; return length; diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index d3c1c250d..9ed0ef2bb 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -244,7 +244,7 @@ static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle int32_t respReceived; // Send object depending on if a response is needed - if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_REQ) + if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_ACK_TS || type == UAVTALK_TYPE_OBJ_REQ) { // Get transaction lock (will block if a transaction is pending) xSemaphoreTakeRecursive(connection->transLock, portMAX_DELAY); @@ -273,10 +273,10 @@ static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle return 0; } } - else if (type == UAVTALK_TYPE_OBJ) + else if (type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_TS) { xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); - sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); + sendObject(connection, obj, instId, type); xSemaphoreGiveRecursive(connection->lock); return 0; } @@ -609,7 +609,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui // Process message type switch (type) { - case UAVTALK_TYPE_OBJ: + case UAVTALK_TYPE_OBJ | UAVTALK_TYPE_OBJ_TS: // All instances, not allowed for OBJ messages if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { @@ -623,7 +623,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui ret = -1; } break; - case UAVTALK_TYPE_OBJ_ACK: + case UAVTALK_TYPE_OBJ_ACK | UAVTALK_TYPE_OBJ_ACK_TS: // All instances, not allowed for OBJ_ACK messages if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { @@ -708,7 +708,7 @@ static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, u } // Process message type - if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_ACK ) + if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_TS || type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_ACK_TS ) { if (instId == UAVOBJ_ALL_INSTANCES) { From 4809d569c028d3a75950c889cf6ddc6e332a1ac5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 03:44:03 -0500 Subject: [PATCH 165/508] Need to tell UAVTalk to expect a longer packet when it includes a timestamp --- flight/UAVTalk/inc/uavtalk_priv.h | 1 + flight/UAVTalk/uavtalk.c | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index 5ed872e1e..e12df0fcf 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -64,6 +64,7 @@ typedef struct { uint16_t instId; uint32_t length; uint8_t instanceLength; + uint8_t timestampLength; uint8_t cs; uint16_t timestamp; int32_t rxCount; diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 9ed0ef2bb..135b41e55 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -390,6 +390,7 @@ UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle { iproc->length = UAVObjGetNumBytes(iproc->obj); iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); + iproc->timestampLength = (iproc->type & UAVTALK_TIMESTAMPED) ? 2 : 0; } else { @@ -408,7 +409,7 @@ UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle } // Check the lengths match - if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size) + if ((iproc->rxPacketLength + iproc->instanceLength + iproc->timestampLength + iproc->length) != iproc->packet_size) { // packet error - mismatched packet size connection->stats.rxErrors++; iproc->state = UAVTALK_STATE_ERROR; From 92d975e6683c702b5eb977aac2dab0043fc295b7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 03:44:35 -0500 Subject: [PATCH 166/508] Reduce the UAVTalk type mask to allow the top byte flag to indicate if there is a timestamp --- flight/UAVTalk/inc/uavtalk_priv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index e12df0fcf..ba107e970 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -91,7 +91,7 @@ typedef struct { #define UAVTALK_WAITFOREVER -1 #define UAVTALK_NOWAIT 0 #define UAVTALK_SYNC_VAL 0x3C -#define UAVTALK_TYPE_MASK 0xF8 +#define UAVTALK_TYPE_MASK 0x78 #define UAVTALK_TYPE_VER 0x20 #define UAVTALK_TIMESTAMPED 0x80 #define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00) From d75fef52eeab30ee0017c0180c828ca4e8080852 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 09:46:49 -0500 Subject: [PATCH 167/508] Increase the overo event queue size to try and stop getting warnings. Only allocate when using overosync. --- flight/Modules/OveroSync/overosync.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 9e5bb8298..3122b76ed 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -38,7 +38,7 @@ // Private constants #define OVEROSYNC_PACKET_SIZE 1024 -#define MAX_QUEUE_SIZE 60 +#define MAX_QUEUE_SIZE 200 #define STACK_SIZE_BYTES 512 #define TASK_PRIORITY (tskIDLE_PRIORITY + 0) @@ -88,6 +88,9 @@ int32_t OveroSyncInitialize(void) if (optionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { overoEnabled = true; + + // Create object queues + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); } else { overoEnabled = false; return -1; @@ -97,8 +100,6 @@ int32_t OveroSyncInitialize(void) OveroSyncStatsInitialize(); - // Create object queues - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); // Initialise UAVTalk uavTalkCon = UAVTalkInitialize(&packData); From e006ae2b4decedce91544d5791899cc53bd5e10a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 11:07:40 -0500 Subject: [PATCH 168/508] Fix a really stupid bug where I ordered two cases together; --- flight/UAVTalk/uavtalk.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 135b41e55..98a2081ac 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -610,7 +610,8 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui // Process message type switch (type) { - case UAVTALK_TYPE_OBJ | UAVTALK_TYPE_OBJ_TS: + case UAVTALK_TYPE_OBJ: + case UAVTALK_TYPE_OBJ_TS: // All instances, not allowed for OBJ messages if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { @@ -624,7 +625,8 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui ret = -1; } break; - case UAVTALK_TYPE_OBJ_ACK | UAVTALK_TYPE_OBJ_ACK_TS: + case UAVTALK_TYPE_OBJ_ACK: + case UAVTALK_TYPE_OBJ_ACK_TS: // All instances, not allowed for OBJ_ACK messages if (obj && (instId != UAVOBJ_ALL_INSTANCES)) { From a90dd1ef5c41d352c6069424ae0136352808b78d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 11:18:58 -0500 Subject: [PATCH 169/508] For now do not call PIOS_OVERO_WriteData from the Tx method because this is too slow (task yield?) and results in a lot of event system errors. --- flight/PiOS/STM32F4xx/pios_overo.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index 1e25ab534..e2b23b665 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -324,7 +324,7 @@ static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) // DMA TX enable (enable IRQ) ? // Load any pending bytes from TX fifo - PIOS_OVERO_WriteData(overo_dev); + //PIOS_OVERO_WriteData(overo_dev); } static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) From 6561b9b164e587a6bf30db44d83dd103c4415569 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 11:28:31 -0500 Subject: [PATCH 170/508] For now make it an error when GPS is enabled but missing. However, no warnings when it's present. --- flight/Modules/GPS/GPS.c | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index de2dda5a9..2a61648aa 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -242,7 +242,7 @@ static void gpsTask(void *parameters) // either the GPS is not plugged in or a hardware problem or the GPS has locked up. uint8_t status = GPSPOSITION_STATUS_NOGPS; GPSPositionStatusSet(&status); - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); + AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); } else { // we appear to be receiving GPS sentences OK, we've had an update //criteria for GPS-OK taken from this post... @@ -257,10 +257,7 @@ static void gpsTask(void *parameters) if (home.Set == HOMELOCATION_SET_FALSE) setHomeLocation(&gpsposition); #endif - } else if (gpsposition.Status == GPSPOSITION_STATUS_FIX3D) - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); - else - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING); + } } } From 30085d23fff44ad8def4944774ed3dd95cee4ee7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 11:29:24 -0500 Subject: [PATCH 171/508] Reenable sending from the overo tx method but no longer yield since we aren't using a blocking write anyway. --- flight/PiOS/STM32F4xx/pios_overo.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index e2b23b665..d45a461fc 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -127,9 +127,11 @@ static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev) bytes_added = (overo_dev->tx_out_cb)(overo_dev->tx_out_context, writing_pointer, max_bytes, NULL, &tx_need_yield); +#if OVERO_USES_BLOCKING_WRITE if (tx_need_yield) { vPortYieldFromISR(); } +#endif overo_dev->writing_offset += bytes_added; } } @@ -324,7 +326,7 @@ static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) // DMA TX enable (enable IRQ) ? // Load any pending bytes from TX fifo - //PIOS_OVERO_WriteData(overo_dev); + PIOS_OVERO_WriteData(overo_dev); } static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) From 82219d2511dc600a1a52a3022288048b7a2c3138 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 14:08:14 -0500 Subject: [PATCH 172/508] Make matlab log processing support overo UAVtalk packets now --- .../plugins/uavobjects/uavobjecttemplate.m | 22 ++++++++++++------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m index 42d388a31..0f9ead8a5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m @@ -60,6 +60,7 @@ $(ALLOCATIONCODE) fid = fopen(logfile); correctMsgByte=hex2dec('20'); +correctTimestampedByte=hex2dec('A0'); correctSyncByte=hex2dec('3C'); unknownObjIDList=zeros(1,2); @@ -83,13 +84,9 @@ while (1) continue end - %% Process header if we are aligned - timestamp = typecast(uint8(prebuf(1:4)), 'uint32'); - datasize = typecast(uint8(prebuf(5:12)), 'uint64'); - % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? msgType = fread(fid, 1, 'uint8'); - if msgType ~= correctMsgByte + if msgType ~= correctMsgByte && msgType ~= hex2dec('A0') wrongMessageByte = wrongMessageByte + 1; continue end @@ -98,7 +95,15 @@ while (1) msgSize = fread(fid, 1, 'uint16'); % get obj id (quint32 4 bytes) objID = fread(fid, 1, 'uint32'); - + + if msgType == correctMsgByte + %% Process header if we are aligned + timestamp = typecast(uint8(prebuf(1:4)), 'uint32'); + datasize = typecast(uint8(prebuf(5:12)), 'uint64'); + elseif msgType == correctTimestampedByte + timestamp = fread(fid,1,'uint16'); + end + if (isempty(objID)) %End of file break; end @@ -153,8 +158,9 @@ $(SWITCHCODE) fprintf([str1 str2 str3 str4 str5]); end - - prebuf = fread(fid, 12, 'uint8'); + if msgType ~= correctTimestampedByte + prebuf = fread(fid, 12, 'uint8'); + end end fprintf('%d records in %0.2f seconds.\n', ftell(fid), etime(clock,startTime)); From 36fcdcc107b8ac495a5bd59ad389a26204292754 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 14:10:05 -0500 Subject: [PATCH 173/508] Make PH use axis lock by default --- flight/Modules/VtolPathFollower/vtolpathfollower.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 4ccff790a..65e3bb812 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -502,7 +502,7 @@ static void updateVtolDesiredAttitude() stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK; StabilizationDesiredSet(&stabDesired); } From 8ac31808b95c29c02070b1c0cac158ceee6e0c1e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 14:11:05 -0500 Subject: [PATCH 174/508] Overo bump --- overo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/overo b/overo index 584f4978e..21ff30e62 160000 --- a/overo +++ b/overo @@ -1 +1 @@ -Subproject commit 584f4978ef2d8912f06881e784dc1fd26e707c77 +Subproject commit 21ff30e625e699bc1a150e5a7fa86588d9df6262 From d1e6dcc2f0b09f712ff59f4e56a9a7fa4f823e00 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 10:50:32 -0500 Subject: [PATCH 175/508] First pass implementation of William Premerlani's magnetometer bias correction --- flight/Modules/Sensors/sensors.c | 60 ++++++++++++++++++- flight/Revolution/UAVObjects.inc | 1 + .../src/plugins/uavobjects/uavobjects.pro | 2 + shared/uavobjectdefinition/magbias.xml | 12 ++++ 4 files changed, 74 insertions(+), 1 deletion(-) create mode 100644 shared/uavobjectdefinition/magbias.xml diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index c5fe3f351..bb3b4bef9 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -49,6 +49,7 @@ #include "pios.h" #include "attitude.h" #include "magnetometer.h" +#include "magbias.h" #include "accels.h" #include "gyros.h" #include "gyrosbias.h" @@ -63,7 +64,7 @@ #include // Private constants -#define STACK_SIZE_BYTES 700 +#define STACK_SIZE_BYTES 1000 #define TASK_PRIORITY (tskIDLE_PRIORITY+3) #define SENSOR_PERIOD 2 @@ -80,6 +81,7 @@ static bool baro_updated = false; static void SensorsTask(void *parameters); static void settingsUpdatedCb(UAVObjEvent * objEv); static void sensorsUpdatedCb(UAVObjEvent * objEv); +static void magOffsetEstimation(MagnetometerData *mag); // These values are initialized by settings but can be updated by the attitude algorithm static bool bias_correct_gyro = true; @@ -111,6 +113,7 @@ int32_t SensorsInitialize(void) GyrosBiasInitialize(); AccelsInitialize(); MagnetometerInitialize(); + MagBiasInitialize(); RevoCalibrationInitialize(); AttitudeSettingsInitialize(); @@ -407,6 +410,9 @@ static void SensorsTask(void *parameters) mag.y = mags[1]; mag.z = mags[2]; } + + // Correct for mag bias and update + //magOffsetEstimation(&mag); MagnetometerSet(&mag); mag_update_time = PIOS_DELAY_GetRaw(); } @@ -418,6 +424,58 @@ static void SensorsTask(void *parameters) } } +/** + * Perform an update of the @ref MagBias based on + * Magnetometer Offset Cancellation: Theory and Implementation, + * revisited William Premerlani, October 14, 2011 + */ +static void magOffsetEstimation(MagnetometerData *mag) +{ + // Constants, to possibly go into a UAVO + static const int UPDATE_INTERVAL = 10; + static const float MIN_NORM_DIFFERENCE = 5; + static const float CONVERGENCE_RATE = 1.0f; + + static unsigned int call_count = 0; + static float B2[3] = {0, 0, 0}; + + call_count++; + + MagBiasData magBias; + MagBiasGet(&magBias); + + // Remove the current estimate of the bias + mag->x -= magBias.x; + mag->y -= magBias.y; + mag->z -= magBias.z; + + // First call + if (B2[0] == 0 && B2[1] == 0 && B2[2] == 0) { + B2[0] = mag->x; + B2[1] = mag->y; + B2[2] = mag->z; + return; + } + if (call_count % UPDATE_INTERVAL == 0) { + float B1[3] = {mag->x, mag->y, mag->z}; + float norm_diff = sqrtf(powf(B2[0] - B1[0],2) + powf(B2[1] - B1[1],2) + powf(B2[2] - B1[2],2)); + if (norm_diff > MIN_NORM_DIFFERENCE) { + float norm_b1 = sqrtf(B1[0]*B1[0] + B1[1]*B1[1] + B1[2]*B1[2]); + float norm_b2 = sqrtf(B2[0]*B2[0] + B2[1]*B2[1] + B2[2]*B2[2]); + float scale = CONVERGENCE_RATE * (norm_b2 - norm_b1) / norm_diff; + float b_error[3] = {(B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale}; + + magBias.x += b_error[0]; + magBias.y += b_error[1]; + magBias.z += b_error[2]; + MagBiasSet(&magBias); + } + + // Store this value to compare against next update + B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; + } +} + /** * Indicate that these sensors have been updated */ diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index be2b4b873..5b99daef4 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -35,6 +35,7 @@ UAVOBJSRCFILENAMES += gyros UAVOBJSRCFILENAMES += gyrosbias UAVOBJSRCFILENAMES += accels UAVOBJSRCFILENAMES += magnetometer +UAVOBJSRCFILENAMES += magbias UAVOBJSRCFILENAMES += baroaltitude UAVOBJSRCFILENAMES += baroairspeed UAVOBJSRCFILENAMES += fixedwingpathfollowersettings diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index d978d0814..70f120115 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -38,6 +38,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/gyrosbias.h \ $$UAVOBJECT_SYNTHETICS/accels.h \ $$UAVOBJECT_SYNTHETICS/magnetometer.h \ + $$UAVOBJECT_SYNTHETICS/magbias.h \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.h \ @@ -110,6 +111,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/gyros.cpp \ $$UAVOBJECT_SYNTHETICS/gyrosbias.cpp \ $$UAVOBJECT_SYNTHETICS/magnetometer.cpp \ + $$UAVOBJECT_SYNTHETICS/magbias.cpp \ $$UAVOBJECT_SYNTHETICS/camerastabsettings.cpp \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.cpp \ $$UAVOBJECT_SYNTHETICS/systemstats.cpp \ diff --git a/shared/uavobjectdefinition/magbias.xml b/shared/uavobjectdefinition/magbias.xml new file mode 100644 index 000000000..63319466f --- /dev/null +++ b/shared/uavobjectdefinition/magbias.xml @@ -0,0 +1,12 @@ + + + The gyro data. + + + + + + + + + From 1a5af9dafbcb56f5796e44edd988087252a30159 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 11:09:38 -0500 Subject: [PATCH 176/508] Remove some old debugging code --- flight/Modules/Sensors/sensors.c | 22 ---------------------- 1 file changed, 22 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index bb3b4bef9..8e865c5a7 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -57,8 +57,6 @@ #include "attitudesettings.h" #include "revocalibration.h" #include "flightstatus.h" -#include "gpsposition.h" -#include "baroaltitude.h" #include "CoordinateConversions.h" #include @@ -74,13 +72,10 @@ // Private variables static xTaskHandle sensorsTaskHandle; -static bool gps_updated = false; -static bool baro_updated = false; // Private functions static void SensorsTask(void *parameters); static void settingsUpdatedCb(UAVObjEvent * objEv); -static void sensorsUpdatedCb(UAVObjEvent * objEv); static void magOffsetEstimation(MagnetometerData *mag); // These values are initialized by settings but can be updated by the attitude algorithm @@ -209,12 +204,6 @@ static void SensorsTask(void *parameters) } } - // If debugging connect callback - if(pios_com_aux_id != 0) { - BaroAltitudeConnectCallback(&sensorsUpdatedCb); - GPSPositionConnectCallback(&sensorsUpdatedCb); - } - // Main task loop lastSysTime = xTaskGetTickCount(); bool error = false; @@ -476,17 +465,6 @@ static void magOffsetEstimation(MagnetometerData *mag) } } -/** - * Indicate that these sensors have been updated - */ -static void sensorsUpdatedCb(UAVObjEvent * objEv) -{ - if(objEv->obj == GPSPositionHandle()) - gps_updated = true; - if(objEv->obj == BaroAltitudeHandle()) - baro_updated = true; -} - /** * Locally cache some variables from the AtttitudeSettings object */ From 3b57b492d059e4a2e189d58875c913edfbc6a943 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 11:19:39 -0500 Subject: [PATCH 177/508] Mag bias tracking seems to work --- flight/Modules/Sensors/sensors.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 8e865c5a7..36546de30 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -401,7 +401,7 @@ static void SensorsTask(void *parameters) } // Correct for mag bias and update - //magOffsetEstimation(&mag); + magOffsetEstimation(&mag); MagnetometerSet(&mag); mag_update_time = PIOS_DELAY_GetRaw(); } @@ -457,6 +457,7 @@ static void magOffsetEstimation(MagnetometerData *mag) magBias.x += b_error[0]; magBias.y += b_error[1]; magBias.z += b_error[2]; + MagBiasSet(&magBias); } From c587ceebfdb75b44b95fe1aa3b60d19dbf1e58fa Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 11:23:27 -0500 Subject: [PATCH 178/508] Make the mag offset nulling convergence rate come from the UAVO. When it is set to zero nulling does not occur to allow us to still calibrate the sensors. --- flight/Modules/Sensors/sensors.c | 25 +++++++++++++------ .../uavobjectdefinition/revocalibration.xml | 6 ++++- 2 files changed, 23 insertions(+), 8 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 36546de30..f062fd148 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -70,14 +70,16 @@ #define PI_MOD(x) (fmodf(x + F_PI, F_PI * 2) - F_PI) // Private types -// Private variables -static xTaskHandle sensorsTaskHandle; // Private functions static void SensorsTask(void *parameters); static void settingsUpdatedCb(UAVObjEvent * objEv); static void magOffsetEstimation(MagnetometerData *mag); +// Private variables +static xTaskHandle sensorsTaskHandle; +RevoCalibrationData cal; + // These values are initialized by settings but can be updated by the attitude algorithm static bool bias_correct_gyro = true; @@ -400,8 +402,10 @@ static void SensorsTask(void *parameters) mag.z = mags[2]; } - // Correct for mag bias and update - magOffsetEstimation(&mag); + // Correct for mag bias and update if the rate is non zero + if(cal.MagBiasNullingRate > 0) + magOffsetEstimation(&mag); + MagnetometerSet(&mag); mag_update_time = PIOS_DELAY_GetRaw(); } @@ -423,7 +427,6 @@ static void magOffsetEstimation(MagnetometerData *mag) // Constants, to possibly go into a UAVO static const int UPDATE_INTERVAL = 10; static const float MIN_NORM_DIFFERENCE = 5; - static const float CONVERGENCE_RATE = 1.0f; static unsigned int call_count = 0; static float B2[3] = {0, 0, 0}; @@ -451,7 +454,7 @@ static void magOffsetEstimation(MagnetometerData *mag) if (norm_diff > MIN_NORM_DIFFERENCE) { float norm_b1 = sqrtf(B1[0]*B1[0] + B1[1]*B1[1] + B1[2]*B1[2]); float norm_b2 = sqrtf(B2[0]*B2[0] + B2[1]*B2[1] + B2[2]*B2[2]); - float scale = CONVERGENCE_RATE * (norm_b2 - norm_b1) / norm_diff; + float scale = cal.MagBiasNullingRate * (norm_b2 - norm_b1) / norm_diff; float b_error[3] = {(B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale}; magBias.x += b_error[0]; @@ -470,7 +473,6 @@ static void magOffsetEstimation(MagnetometerData *mag) * Locally cache some variables from the AtttitudeSettings object */ static void settingsUpdatedCb(UAVObjEvent * objEv) { - RevoCalibrationData cal; RevoCalibrationGet(&cal); mag_bias[0] = cal.mag_bias[REVOCALIBRATION_MAG_BIAS_X]; @@ -487,6 +489,15 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { accel_scale[2] = cal.accel_scale[REVOCALIBRATION_ACCEL_SCALE_Z]; // Do not store gyros_bias here as that comes from the state estimator and should be // used from GyroBias directly + + // Zero out any adaptive tracking + MagBiasData magBias; + MagBiasGet(&magBias); + magBias.x = 0; + magBias.y = 0; + magBias.z = 0; + MagBiasSet(&magBias); + AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); diff --git a/shared/uavobjectdefinition/revocalibration.xml b/shared/uavobjectdefinition/revocalibration.xml index ee5722b6f..481190b5a 100644 --- a/shared/uavobjectdefinition/revocalibration.xml +++ b/shared/uavobjectdefinition/revocalibration.xml @@ -1,7 +1,7 @@ Settings for the INS to control the algorithm and what is updated - + @@ -18,6 +18,10 @@ + + + + From 41f80eb34f60d2636a28edb0ef634a85f1105b99 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 11:26:37 -0500 Subject: [PATCH 179/508] Disable offset nulling while performing GCS mag calibration. --- ground/openpilotgcs/src/plugins/config/configrevowidget.cpp | 6 ++++++ ground/openpilotgcs/src/plugins/config/configrevowidget.h | 1 + 2 files changed, 7 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 84be939d0..0f28dba51 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -535,6 +535,10 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; + // Disable adaptive mag nulling + initialMagCorrectionRate = revoCalibrationData.MagBiasNullingRate; + revoCalibrationData.MagBiasNullingRate = 0; + revoCalibration->setData(revoCalibrationData); Thread::usleep(100000); @@ -740,6 +744,8 @@ void ConfigRevoWidget::computeScaleBias() revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; + // Restore the previous setting + revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate; #ifdef SIX_POINT_CAL_ACCEL bool good_calibration = true; diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index ae5bcf830..7621c6fb7 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -95,6 +95,7 @@ private: UAVObject::Metadata initialGyrosMdata; UAVObject::Metadata initialMagMdata; UAVObject::Metadata initialBaroMdata; + float initialMagCorrectionRate; int position; From 735c0098436f56c79d486eab327da327ccf1a3bf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 13:14:59 -0500 Subject: [PATCH 180/508] Disable writing to the overo driver for every pios_com write again. It drives up system consumption too much, although now data will get lost :(. --- flight/PiOS/STM32F4xx/pios_overo.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/STM32F4xx/pios_overo.c b/flight/PiOS/STM32F4xx/pios_overo.c index d45a461fc..c535d413e 100644 --- a/flight/PiOS/STM32F4xx/pios_overo.c +++ b/flight/PiOS/STM32F4xx/pios_overo.c @@ -127,7 +127,7 @@ static void PIOS_OVERO_WriteData(struct pios_overo_dev *overo_dev) bytes_added = (overo_dev->tx_out_cb)(overo_dev->tx_out_context, writing_pointer, max_bytes, NULL, &tx_need_yield); -#if OVERO_USES_BLOCKING_WRITE +#if defined(OVERO_USES_BLOCKING_WRITE) if (tx_need_yield) { vPortYieldFromISR(); } @@ -326,7 +326,7 @@ static void PIOS_OVERO_TxStart(uint32_t overo_id, uint16_t tx_bytes_avail) // DMA TX enable (enable IRQ) ? // Load any pending bytes from TX fifo - PIOS_OVERO_WriteData(overo_dev); + //PIOS_OVERO_WriteData(overo_dev); } static void PIOS_OVERO_RegisterRxCallback(uint32_t overo_id, pios_com_callback rx_in_cb, uint32_t context) From 0ed5b84ee9d1f76e38552f084c27534bd757a522 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 25 Jul 2012 14:41:10 -0500 Subject: [PATCH 181/508] Move the try catch when parsing overo files --- .../src/plugins/uavobjects/uavobjecttemplate.m | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m index 0f9ead8a5..3dd62df2f 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m @@ -75,14 +75,15 @@ startTime=clock; while (1) if (feof(fid)); break; end + try %% Read message header % get sync field (0x3C, 1 byte) sync = fread(fid, 1, 'uint8'); if sync ~= correctSyncByte - prebuf = [prebuf(2:end); sync]; - wrongSyncByte = wrongSyncByte + 1; - continue - end + prebuf = [prebuf(2:end); sync]; + wrongSyncByte = wrongSyncByte + 1; + continue + end % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? msgType = fread(fid, 1, 'uint8'); @@ -109,7 +110,7 @@ while (1) end %% Read object - try + switch objID $(SWITCHCODE) otherwise From 880d58e4d913ab1bd74803abdad7bfa8f1105a1e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 26 Jul 2012 16:43:24 -0500 Subject: [PATCH 182/508] Changes to mag nulling from D-Lite. Perform update only when we have a new vector sufficiently different from the previous one. --- flight/Modules/Sensors/sensors.c | 33 ++++++++++++++------------------ 1 file changed, 14 insertions(+), 19 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index f062fd148..deb7145ba 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -425,14 +425,10 @@ static void SensorsTask(void *parameters) static void magOffsetEstimation(MagnetometerData *mag) { // Constants, to possibly go into a UAVO - static const int UPDATE_INTERVAL = 10; - static const float MIN_NORM_DIFFERENCE = 5; + static const float MIN_NORM_DIFFERENCE = 50; - static unsigned int call_count = 0; static float B2[3] = {0, 0, 0}; - call_count++; - MagBiasData magBias; MagBiasGet(&magBias); @@ -448,21 +444,20 @@ static void magOffsetEstimation(MagnetometerData *mag) B2[2] = mag->z; return; } - if (call_count % UPDATE_INTERVAL == 0) { - float B1[3] = {mag->x, mag->y, mag->z}; - float norm_diff = sqrtf(powf(B2[0] - B1[0],2) + powf(B2[1] - B1[1],2) + powf(B2[2] - B1[2],2)); - if (norm_diff > MIN_NORM_DIFFERENCE) { - float norm_b1 = sqrtf(B1[0]*B1[0] + B1[1]*B1[1] + B1[2]*B1[2]); - float norm_b2 = sqrtf(B2[0]*B2[0] + B2[1]*B2[1] + B2[2]*B2[2]); - float scale = cal.MagBiasNullingRate * (norm_b2 - norm_b1) / norm_diff; - float b_error[3] = {(B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale}; - magBias.x += b_error[0]; - magBias.y += b_error[1]; - magBias.z += b_error[2]; - - MagBiasSet(&magBias); - } + float B1[3] = {mag->x, mag->y, mag->z}; + float norm_diff = sqrtf(powf(B2[0] - B1[0],2) + powf(B2[1] - B1[1],2) + powf(B2[2] - B1[2],2)); + if (norm_diff > MIN_NORM_DIFFERENCE) { + float norm_b1 = sqrtf(B1[0]*B1[0] + B1[1]*B1[1] + B1[2]*B1[2]); + float norm_b2 = sqrtf(B2[0]*B2[0] + B2[1]*B2[1] + B2[2]*B2[2]); + float scale = cal.MagBiasNullingRate * (norm_b2 - norm_b1) / norm_diff; + float b_error[3] = {(B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale}; + + magBias.x += b_error[0]; + magBias.y += b_error[1]; + magBias.z += b_error[2]; + + MagBiasSet(&magBias); // Store this value to compare against next update B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; From 9f00eda1b46852040fd4a6f8c3d59ba81b290058 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 26 Jul 2012 21:00:30 -0500 Subject: [PATCH 183/508] Add the mag offset compensation into into the simulated sensor code --- flight/Modules/Sensors/simulated/sensors.c | 65 +++++++++++++++++++++- 1 file changed, 62 insertions(+), 3 deletions(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index 933e95279..62695e908 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -63,6 +63,7 @@ #include "gpsvelocity.h" #include "homelocation.h" #include "magnetometer.h" +#include "magbias.h" #include "ratedesired.h" #include "revocalibration.h" @@ -87,6 +88,8 @@ static void simulateModelAgnostic(); static void simulateModelQuadcopter(); static void simulateModelAirplane(); +static void magOffsetEstimation(MagnetometerData *mag); + static float accel_bias[3]; static float rand_gauss(); @@ -114,6 +117,7 @@ int32_t SensorsInitialize(void) GPSPositionInitialize(); GPSVelocityInitialize(); MagnetometerInitialize(); + MagBiasInitialize(); RevoCalibrationInitialize(); return 0; @@ -503,6 +507,10 @@ static void simulateModelQuadcopter() mag.x = homeLocation.Be[0] * Rbe[0][0] + homeLocation.Be[1] * Rbe[0][1] + homeLocation.Be[2] * Rbe[0][2]; mag.y = homeLocation.Be[0] * Rbe[1][0] + homeLocation.Be[1] * Rbe[1][1] + homeLocation.Be[2] * Rbe[1][2]; mag.z = homeLocation.Be[0] * Rbe[2][0] + homeLocation.Be[1] * Rbe[2][1] + homeLocation.Be[2] * Rbe[2][2]; + + // Run the offset compensation algorithm from the firmware + magOffsetEstimation(&mag); + MagnetometerSet(&mag); last_mag_time = PIOS_DELAY_GetRaw(); } @@ -779,9 +787,10 @@ static void simulateModelAirplane() static uint32_t last_mag_time = 0; if(PIOS_DELAY_DiffuS(last_mag_time) / 1.0e6 > MAG_PERIOD) { MagnetometerData mag; - mag.x = homeLocation.Be[0] * Rbe[0][0] + homeLocation.Be[1] * Rbe[0][1] + homeLocation.Be[2] * Rbe[0][2]; - mag.y = homeLocation.Be[0] * Rbe[1][0] + homeLocation.Be[1] * Rbe[1][1] + homeLocation.Be[2] * Rbe[1][2]; - mag.z = homeLocation.Be[0] * Rbe[2][0] + homeLocation.Be[1] * Rbe[2][1] + homeLocation.Be[2] * Rbe[2][2]; + mag.x = 100+homeLocation.Be[0] * Rbe[0][0] + homeLocation.Be[1] * Rbe[0][1] + homeLocation.Be[2] * Rbe[0][2]; + mag.y = 100+homeLocation.Be[0] * Rbe[1][0] + homeLocation.Be[1] * Rbe[1][1] + homeLocation.Be[2] * Rbe[1][2]; + mag.z = 100+homeLocation.Be[0] * Rbe[2][0] + homeLocation.Be[1] * Rbe[2][1] + homeLocation.Be[2] * Rbe[2][2]; + magOffsetEstimation(&mag); MagnetometerSet(&mag); last_mag_time = PIOS_DELAY_GetRaw(); } @@ -818,6 +827,56 @@ static float rand_gauss (void) { return (v1*sqrt(-2.0 * log(s) / s)); } +/** + * Perform an update of the @ref MagBias based on + * Magnetometer Offset Cancellation: Theory and Implementation, + * revisited William Premerlani, October 14, 2011 + */ +static void magOffsetEstimation(MagnetometerData *mag) +{ + RevoCalibrationData cal; + RevoCalibrationGet(&cal); + + // Constants, to possibly go into a UAVO + static const float MIN_NORM_DIFFERENCE = 50; + + static float B2[3] = {0, 0, 0}; + + MagBiasData magBias; + MagBiasGet(&magBias); + + // Remove the current estimate of the bias + mag->x -= magBias.x; + mag->y -= magBias.y; + mag->z -= magBias.z; + + // First call + if (B2[0] == 0 && B2[1] == 0 && B2[2] == 0) { + B2[0] = mag->x; + B2[1] = mag->y; + B2[2] = mag->z; + return; + } + + float B1[3] = {mag->x, mag->y, mag->z}; + float norm_diff = sqrtf(powf(B2[0] - B1[0],2) + powf(B2[1] - B1[1],2) + powf(B2[2] - B1[2],2)); + if (norm_diff > MIN_NORM_DIFFERENCE) { + float norm_b1 = sqrtf(B1[0]*B1[0] + B1[1]*B1[1] + B1[2]*B1[2]); + float norm_b2 = sqrtf(B2[0]*B2[0] + B2[1]*B2[1] + B2[2]*B2[2]); + float scale = cal.MagBiasNullingRate * (norm_b2 - norm_b1) / norm_diff; + float b_error[3] = {(B2[0] - B1[0]) * scale, (B2[1] - B1[1]) * scale, (B2[2] - B1[2]) * scale}; + + magBias.x += b_error[0]; + magBias.y += b_error[1]; + magBias.z += b_error[2]; + + MagBiasSet(&magBias); + + // Store this value to compare against next update + B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; + } +} + /** * @} * @} From abb0caa6bd1e437d9d953595b6b76a521ce7d01f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 13:14:18 -0500 Subject: [PATCH 184/508] Try a different mag nulling algorithm. --- flight/Modules/Sensors/sensors.c | 57 ++++++++++++++++++++++ flight/Modules/Sensors/simulated/sensors.c | 51 +++++++++++++++++++ 2 files changed, 108 insertions(+) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index deb7145ba..7fe95f636 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -48,6 +48,7 @@ #include "pios.h" #include "attitude.h" +#include "homelocation.h" #include "magnetometer.h" #include "magbias.h" #include "accels.h" @@ -424,6 +425,7 @@ static void SensorsTask(void *parameters) */ static void magOffsetEstimation(MagnetometerData *mag) { +#if 0 // Constants, to possibly go into a UAVO static const float MIN_NORM_DIFFERENCE = 50; @@ -462,6 +464,61 @@ static void magOffsetEstimation(MagnetometerData *mag) // Store this value to compare against next update B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; } +#else + static uint32_t call_count = 0; + + MagBiasData magBias; + MagBiasGet(&magBias); + + // Remove the current estimate of the bias + mag->x -= magBias.x; + mag->y -= magBias.y; + mag->z -= magBias.z; + + if((call_count++ % 5) == 0) { + HomeLocationData homeLocation; + HomeLocationGet(&homeLocation); + + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + + const float Rxy = sqrtf(homeLocation.Be[0]*homeLocation.Be[0] + homeLocation.Be[1]*homeLocation.Be[1]); + const float Rz = homeLocation.Be[2]; + + const float rate = cal.MagBiasNullingRate; + float R[3][3]; + float B_e[3]; + float xy[2]; + float delta[3]; + + // Get the rotation matrix + Quaternion2R(&attitude.q1, R); + + // Rotate the mag into the NED frame + B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; + B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; + B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; + + float cy = cosf(attitude.Yaw * M_PI / 180.0f); + float sy = sinf(attitude.Yaw * M_PI / 180.0f); + + xy[0] = cy * B_e[0] + sy * B_e[1]; + xy[1] = -sy * B_e[0] + cy * B_e[1]; + + float xy_norm = sqrtf(xy[0]*xy[0] + xy[1]*xy[1]); + + delta[0] = -rate * (xy[0] / xy_norm * Rxy - xy[0]); + delta[1] = -rate * (xy[1] / xy_norm * Rxy - xy[1]); + delta[2] = -rate * (Rz - B_e[2]); + + if (delta[0] == delta[0] && delta[1] == delta[1] && delta[2] == delta[2]) { + magBias.x += delta[0]; + magBias.y += delta[1]; + magBias.z += delta[2]; + MagBiasSet(&magBias); + } + } +#endif } /** diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index 62695e908..9dadd7477 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -834,6 +834,7 @@ static float rand_gauss (void) { */ static void magOffsetEstimation(MagnetometerData *mag) { +#if 0 RevoCalibrationData cal; RevoCalibrationGet(&cal); @@ -875,6 +876,56 @@ static void magOffsetEstimation(MagnetometerData *mag) // Store this value to compare against next update B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; } +#else + HomeLocationData homeLocation; + HomeLocationGet(&homeLocation); + + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + + MagBiasData magBias; + MagBiasGet(&magBias); + + // Remove the current estimate of the bias + mag->x -= magBias.x; + mag->y -= magBias.y; + mag->z -= magBias.z; + + const float Rxy = sqrtf(homeLocation.Be[0]*homeLocation.Be[0] + homeLocation.Be[1]*homeLocation.Be[1]); + const float Rz = homeLocation.Be[2]; + + const float rate = 0.01; + float R[3][3]; + float B_e[3]; + float xy[2]; + float delta[3]; + + // Get the rotation matrix + Quaternion2R(&attitude.q1, R); + + // Rotate the mag into the NED frame + B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; + B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; + B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; + + float cy = cosf(attitude.Yaw * M_PI / 180.0f); + float sy = sinf(attitude.Yaw * M_PI / 180.0f); + + xy[0] = cy * B_e[0] + sy * B_e[1]; + xy[1] = -sy * B_e[0] + cy * B_e[1]; + + float xy_norm = sqrtf(xy[0]*xy[0] + xy[1]*xy[1]); + + delta[0] = -rate * (xy[0] / xy_norm * Rxy - xy[0]); + delta[1] = -rate * (xy[1] / xy_norm * Rxy - xy[1]); + delta[2] = -rate * (Rz - B_e[2]); + + magBias.x += delta[0]; + magBias.y += delta[1]; + magBias.z += delta[2]; + MagBiasSet(&magBias); +#endif + } /** From 221ae05ef6c405c6ad6e33dc810876eb39e77fe5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 13:20:30 -0500 Subject: [PATCH 185/508] Perform the update every cycle. Mag rate of 0.001 seems to work well. --- flight/Modules/Sensors/sensors.c | 86 +++++++++++++++----------------- 1 file changed, 41 insertions(+), 45 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 7fe95f636..22d22b250 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -465,8 +465,6 @@ static void magOffsetEstimation(MagnetometerData *mag) B2[0] = B1[0]; B2[1] = B1[1]; B2[2] = B1[2]; } #else - static uint32_t call_count = 0; - MagBiasData magBias; MagBiasGet(&magBias); @@ -474,49 +472,47 @@ static void magOffsetEstimation(MagnetometerData *mag) mag->x -= magBias.x; mag->y -= magBias.y; mag->z -= magBias.z; - - if((call_count++ % 5) == 0) { - HomeLocationData homeLocation; - HomeLocationGet(&homeLocation); - - AttitudeActualData attitude; - AttitudeActualGet(&attitude); - - const float Rxy = sqrtf(homeLocation.Be[0]*homeLocation.Be[0] + homeLocation.Be[1]*homeLocation.Be[1]); - const float Rz = homeLocation.Be[2]; - - const float rate = cal.MagBiasNullingRate; - float R[3][3]; - float B_e[3]; - float xy[2]; - float delta[3]; - - // Get the rotation matrix - Quaternion2R(&attitude.q1, R); - - // Rotate the mag into the NED frame - B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; - B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; - B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; - - float cy = cosf(attitude.Yaw * M_PI / 180.0f); - float sy = sinf(attitude.Yaw * M_PI / 180.0f); - - xy[0] = cy * B_e[0] + sy * B_e[1]; - xy[1] = -sy * B_e[0] + cy * B_e[1]; - - float xy_norm = sqrtf(xy[0]*xy[0] + xy[1]*xy[1]); - - delta[0] = -rate * (xy[0] / xy_norm * Rxy - xy[0]); - delta[1] = -rate * (xy[1] / xy_norm * Rxy - xy[1]); - delta[2] = -rate * (Rz - B_e[2]); - - if (delta[0] == delta[0] && delta[1] == delta[1] && delta[2] == delta[2]) { - magBias.x += delta[0]; - magBias.y += delta[1]; - magBias.z += delta[2]; - MagBiasSet(&magBias); - } + + HomeLocationData homeLocation; + HomeLocationGet(&homeLocation); + + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + + const float Rxy = sqrtf(homeLocation.Be[0]*homeLocation.Be[0] + homeLocation.Be[1]*homeLocation.Be[1]); + const float Rz = homeLocation.Be[2]; + + const float rate = cal.MagBiasNullingRate; + float R[3][3]; + float B_e[3]; + float xy[2]; + float delta[3]; + + // Get the rotation matrix + Quaternion2R(&attitude.q1, R); + + // Rotate the mag into the NED frame + B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; + B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; + B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; + + float cy = cosf(attitude.Yaw * M_PI / 180.0f); + float sy = sinf(attitude.Yaw * M_PI / 180.0f); + + xy[0] = cy * B_e[0] + sy * B_e[1]; + xy[1] = -sy * B_e[0] + cy * B_e[1]; + + float xy_norm = sqrtf(xy[0]*xy[0] + xy[1]*xy[1]); + + delta[0] = -rate * (xy[0] / xy_norm * Rxy - xy[0]); + delta[1] = -rate * (xy[1] / xy_norm * Rxy - xy[1]); + delta[2] = -rate * (Rz - B_e[2]); + + if (delta[0] == delta[0] && delta[1] == delta[1] && delta[2] == delta[2]) { + magBias.x += delta[0]; + magBias.y += delta[1]; + magBias.z += delta[2]; + MagBiasSet(&magBias); } #endif } From f02aacfeb6147757df6e5754bed0947f916aa0f0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 11:22:24 -0500 Subject: [PATCH 186/508] Change the constant so LED flashing works properly on Revo --- flight/PiOS/Common/pios_flash_jedec.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/flight/PiOS/Common/pios_flash_jedec.c b/flight/PiOS/Common/pios_flash_jedec.c index ed4a6390b..4af779f1a 100644 --- a/flight/PiOS/Common/pios_flash_jedec.c +++ b/flight/PiOS/Common/pios_flash_jedec.c @@ -333,8 +333,11 @@ int32_t PIOS_Flash_Jedec_EraseChip() while(PIOS_Flash_Jedec_Busy() != 0) { #if defined(FLASH_FREERTOS) vTaskDelay(1); -#endif + if ((i++) % 100 == 0) +#else if ((i++) % 10000 == 0) +#endif + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); } From 61c177186207d0d6b763998ce06c6e200279dc5b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 11:22:24 -0500 Subject: [PATCH 187/508] Change the constant so LED flashing works properly on Revo --- flight/PiOS/Common/pios_flash_jedec.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/flight/PiOS/Common/pios_flash_jedec.c b/flight/PiOS/Common/pios_flash_jedec.c index ed4a6390b..4af779f1a 100644 --- a/flight/PiOS/Common/pios_flash_jedec.c +++ b/flight/PiOS/Common/pios_flash_jedec.c @@ -333,8 +333,11 @@ int32_t PIOS_Flash_Jedec_EraseChip() while(PIOS_Flash_Jedec_Busy() != 0) { #if defined(FLASH_FREERTOS) vTaskDelay(1); -#endif + if ((i++) % 100 == 0) +#else if ((i++) % 10000 == 0) +#endif + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); } From 9bd49ded4f3da0300229759d4e343787769d98d1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 13:35:31 -0500 Subject: [PATCH 188/508] OSX Simulator - get model type correctly --- flight/Modules/Sensors/simulated/sensors.c | 22 +++++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index 9dadd7477..acd3a5d53 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -66,6 +66,7 @@ #include "magbias.h" #include "ratedesired.h" #include "revocalibration.h" +#include "systemsettings.h" #include "CoordinateConversions.h" @@ -160,13 +161,32 @@ static void SensorsTask(void *parameters) // homeLocation.Set = HOMELOCATION_SET_TRUE; // HomeLocationSet(&homeLocation); - sensor_sim_type = MODEL_AIRPLANE; // Main task loop lastSysTime = xTaskGetTickCount(); uint32_t last_time = PIOS_DELAY_GetRaw(); while (1) { PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); + + SystemSettingsData systemSettings; + SystemSettingsGet(&systemSettings); + + switch(systemSettings.AirframeType) { + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWING: + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGELEVON: + case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGVTAIL: + sensor_sim_type = MODEL_AIRPLANE; + break; + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: + case SYSTEMSETTINGS_AIRFRAMETYPE_VTOL: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: + sensor_sim_type = MODEL_QUADCOPTER; + break; + default: + sensor_sim_type = MODEL_AGNOSTIC; + } static int i; i++; From 24636eb5f44d777a3856b840f2748cb1c3c20882 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 22:55:59 -0500 Subject: [PATCH 189/508] Add a waypoint above home for the box pattern. --- flight/Modules/PathPlanner/pathplanner.c | 21 ++++++++++++++------- 1 file changed, 14 insertions(+), 7 deletions(-) diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index 1a5ba6f8d..c46cb323e 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -126,6 +126,8 @@ static void pathPlannerTask(void *parameters) continue; } + // This method determines if we have achieved the goal of the active + // waypoint checkTerminationCondition(); if(pathplanner_active == false) { @@ -313,30 +315,35 @@ static void createPathBox() waypoint.Velocity[0] = 2; // Since for now this isn't directional just set a mag waypoint.Action = WAYPOINT_ACTION_PATHTONEXT; - waypoint.Position[0] = 5; - waypoint.Position[1] = 5; + waypoint.Position[0] = 0; + waypoint.Position[1] = 0; waypoint.Position[2] = -10; WaypointInstSet(0, &waypoint); - waypoint.Position[0] = -5; + waypoint.Position[0] = 5; waypoint.Position[1] = 5; + waypoint.Position[2] = -10; WaypointInstSet(1, &waypoint); waypoint.Position[0] = -5; - waypoint.Position[1] = -5; + waypoint.Position[1] = 5; WaypointInstSet(2, &waypoint); - waypoint.Position[0] = 5; + waypoint.Position[0] = -5; waypoint.Position[1] = -5; WaypointInstSet(3, &waypoint); waypoint.Position[0] = 5; - waypoint.Position[1] = 5; + waypoint.Position[1] = -5; WaypointInstSet(4, &waypoint); + waypoint.Position[0] = 5; + waypoint.Position[1] = 5; + WaypointInstSet(5, &waypoint); + waypoint.Position[0] = 0; waypoint.Position[1] = 0; - WaypointInstSet(5, &waypoint); + WaypointInstSet(6, &waypoint); } static void createPathLogo() From 0af240e0a396f54980f1bd80567c25c4e224c07d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 22:57:10 -0500 Subject: [PATCH 190/508] Add a plane/quad directory to ignore for sim_posix files --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index a5af05849..dc058313d 100644 --- a/.gitignore +++ b/.gitignore @@ -71,3 +71,6 @@ GSYMS GTAGS /.cproject /.project + +plane +quad From dde9de080eaa54087acda1905410dd069849e956 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 29 Jul 2012 12:41:20 -0500 Subject: [PATCH 191/508] Need to increase the GPS stack size when I include the GPZDA message --- flight/Modules/GPS/GPS.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 2a61648aa..3a4c9914c 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -66,7 +66,7 @@ static float GravityAccel(float latitude, float longitude, float altitude); #ifdef PIOS_GPS_SETS_HOMELOCATION // Unfortunately need a good size stack for the WMM calculation - #define STACK_SIZE_BYTES 750 + #define STACK_SIZE_BYTES 850 #else #if defined(PIOS_GPS_MINIMAL) #define STACK_SIZE_BYTES 500 From d06b40ea290a32f946cea93dff02ff3050b83f46 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 24 Feb 2011 03:35:19 -0600 Subject: [PATCH 192/508] Initial import of my androidgcs framework --- androidgcs/AndroidManifest.xml | 18 + androidgcs/bin/OpieMobi.apk | Bin 0 -> 148198 bytes androidgcs/bin/classes.dex | Bin 0 -> 12640 bytes .../ObjBrowserExpandableListAdapter.class | Bin 0 -> 3092 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 0 -> 951 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 0 -> 358 bytes .../org/openpilot/androidgcs/R$color.class | Bin 0 -> 447 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 0 -> 418 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 0 -> 403 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 0 -> 449 bytes .../org/openpilot/androidgcs/R$string.class | Bin 0 -> 445 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 0 -> 627 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 0 -> 1127 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 0 -> 1440 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 0 -> 1199 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 0 -> 1333 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 0 -> 2255 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 0 -> 5422 bytes androidgcs/bin/resources.ap_ | Bin 0 -> 140460 bytes androidgcs/default.properties | 11 + .../gen/org/openpilot/androidgcs/R.java | 31 ++ androidgcs/proguard.cfg | 36 ++ androidgcs/res/drawable-hdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/layout/main.xml | 12 + androidgcs/res/layout/objectbrowser.xml | 8 + androidgcs/res/values/strings.xml | 7 + .../ObjBrowserExpandableListAdapter.java | 99 ++++++ .../openpilot/androidgcs/ObjectBrowser.java | 21 ++ .../org/openpilot/uavtalk/UAVDataObject.java | 27 ++ .../org/openpilot/uavtalk/UAVMetaObject.java | 50 +++ .../src/org/openpilot/uavtalk/UAVObject.java | 117 ++++++ .../openpilot/uavtalk/UAVObjectManager.java | 332 ++++++++++++++++++ 34 files changed, 769 insertions(+) create mode 100644 androidgcs/AndroidManifest.xml create mode 100644 androidgcs/bin/OpieMobi.apk create mode 100644 androidgcs/bin/classes.dex create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class create mode 100644 androidgcs/bin/resources.ap_ create mode 100644 androidgcs/default.properties create mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java create mode 100644 androidgcs/proguard.cfg create mode 100644 androidgcs/res/drawable-hdpi/icon.png create mode 100644 androidgcs/res/drawable-ldpi/icon.png create mode 100644 androidgcs/res/drawable-mdpi/icon.png create mode 100644 androidgcs/res/layout/main.xml create mode 100644 androidgcs/res/layout/objectbrowser.xml create mode 100644 androidgcs/res/values/strings.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml new file mode 100644 index 000000000..83d19e96c --- /dev/null +++ b/androidgcs/AndroidManifest.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk new file mode 100644 index 0000000000000000000000000000000000000000..87a15c5e83805a3bb48265a78f9bd9154813cd35 GIT binary patch literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class new file mode 100644 index 0000000000000000000000000000000000000000..306bc08c9eca5d510d01792bc7011e1ef8b75cc0 GIT binary patch literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class new file mode 100644 index 0000000000000000000000000000000000000000..f69a8e17560897ad1adaae18fd15a3f75ac850a4 GIT binary patch literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class new file mode 100644 index 0000000000000000000000000000000000000000..43d486e461eb753c8772c3c239c81b3a83a13216 GIT binary patch literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class new file mode 100644 index 0000000000000000000000000000000000000000..d473cb81c8c6db44be5035f5848de2cfe8504c66 GIT binary patch literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class new file mode 100644 index 0000000000000000000000000000000000000000..95af7d70364676903cbaee10411198d19f52394b GIT binary patch literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class new file mode 100644 index 0000000000000000000000000000000000000000..7234b135ec1e4b601e8d271c48caf5fa07bd47ba GIT binary patch literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class new file mode 100644 index 0000000000000000000000000000000000000000..5e520fa0eb6d9ad0cf329fa2572250588a3e365e GIT binary patch literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class new file mode 100644 index 0000000000000000000000000000000000000000..5e228155303a29cd063056a485473fdd564000c7 GIT binary patch literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class new file mode 100644 index 0000000000000000000000000000000000000000..f4a6dd7e4e5820644e459a4aa5652e5f2a69beba GIT binary patch literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ new file mode 100644 index 0000000000000000000000000000000000000000..2452fd26f12793bb5445461ce339266070961506 GIT binary patch literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u literal 0 HcmV?d00001 diff --git a/androidgcs/default.properties b/androidgcs/default.properties new file mode 100644 index 000000000..e2e8061f2 --- /dev/null +++ b/androidgcs/default.properties @@ -0,0 +1,11 @@ +# This file is automatically generated by Android Tools. +# Do not modify this file -- YOUR CHANGES WILL BE ERASED! +# +# This file must be checked in Version Control Systems. +# +# To customize properties used by the Ant build system use, +# "build.properties", and override values to adapt the script to your +# project structure. + +# Project target. +target=android-8 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java new file mode 100644 index 000000000..31e90ffd1 --- /dev/null +++ b/androidgcs/gen/org/openpilot/androidgcs/R.java @@ -0,0 +1,31 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * aapt tool from the resource data it found. It + * should not be modified by hand. + */ + +package org.openpilot.androidgcs; + +public final class R { + public static final class attr { + } + public static final class color { + public static final int all_black=0x7f050001; + public static final int all_white=0x7f050000; + } + public static final class drawable { + public static final int icon=0x7f020000; + } + public static final class id { + public static final int objects=0x7f060000; + } + public static final class layout { + public static final int main=0x7f030000; + public static final int objectbrowser=0x7f030001; + } + public static final class string { + public static final int app_name=0x7f040001; + public static final int hello=0x7f040000; + } +} diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg new file mode 100644 index 000000000..12dd0392c --- /dev/null +++ b/androidgcs/proguard.cfg @@ -0,0 +1,36 @@ +-optimizationpasses 5 +-dontusemixedcaseclassnames +-dontskipnonpubliclibraryclasses +-dontpreverify +-verbose +-optimizations !code/simplification/arithmetic,!field/*,!class/merging/* + +-keep public class * extends android.app.Activity +-keep public class * extends android.app.Application +-keep public class * extends android.app.Service +-keep public class * extends android.content.BroadcastReceiver +-keep public class * extends android.content.ContentProvider +-keep public class * extends android.app.backup.BackupAgentHelper +-keep public class * extends android.preference.Preference +-keep public class com.android.vending.licensing.ILicensingService + +-keepclasseswithmembernames class * { + native ; +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet); +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet, int); +} + +-keepclassmembers enum * { + public static **[] values(); + public static ** valueOf(java.lang.String); +} + +-keep class * implements android.os.Parcelable { + public static final android.os.Parcelable$Creator *; +} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926
r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml new file mode 100644 index 000000000..3a5f117d3 --- /dev/null +++ b/androidgcs/res/layout/main.xml @@ -0,0 +1,12 @@ + + + + diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml new file mode 100644 index 000000000..02a3f5dd6 --- /dev/null +++ b/androidgcs/res/layout/objectbrowser.xml @@ -0,0 +1,8 @@ + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml new file mode 100644 index 000000000..eba6becf8 --- /dev/null +++ b/androidgcs/res/values/strings.xml @@ -0,0 +1,7 @@ + + + OpenPilot Android GCS + OpieMobi + #FFFFFF + #000000 + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java new file mode 100644 index 000000000..190668d80 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java @@ -0,0 +1,99 @@ +/** + * + */ +package org.openpilot.androidgcs; + +import android.widget.AbsListView; +import android.widget.TextView; +import android.content.Context; +import android.view.Gravity; +import android.view.View; +import android.view.ViewGroup; +import android.widget.BaseExpandableListAdapter; + +/** + * @author jcotton81 + * + */ +public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { + + // Sample data set. children[i] contains the children (String[]) for + // groups[i]. + private String[] groups = { "Parent1", "Parent2", "Parent3" }; + private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; + + private Context context; + + public ObjBrowserExpandableListAdapter(Context context) { + this.context = context; + } + + public Object getChild(int groupPosition, int childPosition) { + return children[groupPosition][childPosition]; + } + + public long getChildId(int groupPosition, int childPosition) { + return childPosition; + } + + public int getChildrenCount(int groupPosition) { + int i = 0; + try { + i = children[groupPosition].length; + + } catch (Exception e) { + } + + return i; + } + + public TextView getGenericView() { + // Layout parameters for the ExpandableListView + AbsListView.LayoutParams lp = new AbsListView.LayoutParams( + ViewGroup.LayoutParams.FILL_PARENT, 64); + + TextView textView = new TextView(context); + textView.setLayoutParams(lp); + // Center the text vertically + textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); + // Set the text starting position + textView.setPadding(36, 0, 0, 0); + return textView; + } + + public View getChildView(int groupPosition, int childPosition, + boolean isLastChild, View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getChild(groupPosition, childPosition).toString()); + return textView; + } + + public Object getGroup(int groupPosition) { + return groups[groupPosition]; + } + + public int getGroupCount() { + return groups.length; + } + + public long getGroupId(int groupPosition) { + return groupPosition; + } + + public View getGroupView(int groupPosition, boolean isExpanded, + View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getGroup(groupPosition).toString()); + return textView; + } + + public boolean isChildSelectable(int groupPosition, int childPosition) { + return true; + } + + public boolean hasStableIds() { + return true; + } + + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..19e9b2812 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,21 @@ +package org.openpilot.androidgcs; + +import android.app.Activity; +import android.os.Bundle; + +import android.widget.*; + +public class ObjectBrowser extends Activity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + setContentView(R.layout.objectbrowser); + ExpandableListAdapter mAdapter; + ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); + mAdapter = new ObjBrowserExpandableListAdapter(this); + epView.setAdapter(mAdapter); + + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java new file mode 100644 index 000000000..12a4263c0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -0,0 +1,27 @@ +package org.openpilot.uavtalk; + +public abstract class UAVDataObject extends UAVObject { + + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(objID, isSingleInst, name); + } + + public void initialize(int instID, UAVMetaObject mobj) { + + } + + public void initialize(UAVMetaObject mobj) { + + } + + Boolean isSettings() { + return null; + } + + UAVMetaObject getMetaObject() { + return null; + } + + public abstract UAVDataObject clone(int instID); + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java new file mode 100644 index 000000000..a1e5773b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -0,0 +1,50 @@ +package org.openpilot.uavtalk; + +public class UAVMetaObject extends UAVObject { + + public UAVMetaObject(int objID, Boolean isSingleInst, String name) { + super(objID, isSingleInst, name); + // TODO Auto-generated constructor stub + } + + public UAVMetaObject(int objID, String mname, UAVDataObject obj) { + // TODO Auto-generated constructor stub + } + + @Override + public void deserialize(byte[] arr, int offset) { + // TODO Auto-generated method stub + + } + + @Override + public UAVMetaObject getDefaultMetadata() { + // TODO Auto-generated method stub + return null; + } + + @Override + public String getDescription() { + // TODO Auto-generated method stub + return null; + } + + @Override + public int getObjID() { + // TODO Auto-generated method stub + return 0; + } + + @Override + public String getObjName() { + // TODO Auto-generated method stub + return null; + } + + @Override + public byte[] serialize() { + // TODO Auto-generated method stub + return null; + } + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java new file mode 100644 index 000000000..c5ffc9d21 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -0,0 +1,117 @@ +package org.openpilot.uavtalk; + +public abstract class UAVObject { + + + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; + + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; + + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; + + public UAVObject(int objID, Boolean isSingleInst, String name) { + assert(objID == getObjID()); // ID is in implementation code, make sure it matches object + assert(name.equals(getName())); + this.isSingleInst = isSingleInst; + meta = getDefaultMetadata(); + }; + + public void initialize(int instID) { + this.instID = instID; + } + + public int getInstID() { return instID; } + public Boolean isSingleInstance() { return isSingleInst; } + public String getName() { return getObjName(); } // matching QT API to the current autogen code + + public abstract int getObjID(); + public abstract String getDescription(); + public abstract String getObjName(); + + int getNumBytes() { + return serialize().length; + } + + // The name of the serializer and deserialize from the autogenerated code + public abstract byte[] serialize(); + public abstract void deserialize(byte[] arr,int offset); + + byte [] pack() { + return serialize(); + } + + Boolean unpack(byte [] data) { + deserialize(data, 0); + return true; + } + + public void setMetadata(UAVMetaObject obj) { meta = obj; } + public UAVMetaObject getMetadata() { return meta; } + public abstract UAVMetaObject getDefaultMetadata(); + + /* + // Unported code from QT + bool save(); + bool save(QFile& file); + bool load(); + bool load(QFile& file); + virtual void setMetadata(const Metadata& mdata) = 0; + virtual Metadata getMetadata() = 0; + virtual Metadata getDefaultMetadata() = 0; + void requestUpdate(); + void updated(); + void lock(); + void lock(int timeoutMs); + void unlock(); + QMutex* getMutex(); + qint32 getNumFields(); + QList getFields(); + UAVObjectField* getField(const QString& name); + QString toString(); + QString toStringBrief(); + QString toStringData(); + void emitTransactionCompleted(bool success); + + signals: + void objectUpdated(UAVObject* obj); + void objectUpdatedAuto(UAVObject* obj); + void objectUpdatedManual(UAVObject* obj); + void objectUnpacked(UAVObject* obj); + void updateRequested(UAVObject* obj); + void transactionCompleted(UAVObject* obj, bool success); + + private slots: + void fieldUpdated(UAVObjectField* field); + + protected: + quint32 objID; + quint32 instID; + bool isSingleInst; + QString name; + QString description; + quint32 numBytes; + QMutex* mutex; + quint8* data; + QList fields; + + void initializeFields(QList& fields, quint8* data, quint32 numBytes); + void setDescription(const QString& description); + */ +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java new file mode 100644 index 000000000..3091595f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -0,0 +1,332 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +public class UAVObjectManager { + + private final int MAX_INSTANCES = 10; + + // Use array list to store objects since rarely added or deleted + private List> objects = new ArrayList>(); + + public UAVObjectManager() + { + //mutex = new QMutex(QMutex::Recursive); + } + + /** + * Register an object with the manager. This function must be called for all newly created instances. + * A new instance can be created directly by instantiating a new object or by calling clone() of + * an existing object. The object will be registered and will be properly initialized so that it can accept + * updates. + */ + Boolean registerObject(UAVDataObject obj) + { + // QMutexLocker locker(mutex); + + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // Check if the object ID is in the list + if( (instList.size() > 0) && (instList.get(0).getObjID() == obj.getObjID() )) { + // Check if this is a single instance object, if yes we can not add a new instance + if(obj.isSingleInstance()) { + return false; + } + // The object type has alredy been added, so now we need to initialize the new instance with the appropriate id + // There is a single metaobject for all object instances of this type, so no need to create a new one + // Get object type metaobject from existing instance + UAVDataObject refObj = (UAVDataObject) instList.get(0); + if (refObj == null) + { + return false; + } + UAVMetaObject mobj = refObj.getMetaObject(); + + // Make sure we aren't requesting to create too many instances + if(obj.getInstID() >= MAX_INSTANCES || instList.size() >= MAX_INSTANCES || obj.getInstID() < 0) { + return false; + } + + // If InstID is zero then we find the next open instId and create it + if (obj.getInstID() == 0) + { + // Assign the next available ID and initialize the object instance the nadd + obj.initialize(instList.size(), mobj); + instList.add(obj); + return true; + } + + // Check if that inst ID already exists + ListIterator instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + // If the instance ID is specified and not at the default value (0) then we need to make sure + // that there are no gaps in the instance list. If gaps are found then then additional instances + // will be created. + for(int instID = instList.size(); instID < obj.getInstID(); instID++) { + UAVDataObject newObj = obj.clone(instID); + newObj.initialize(mobj); + instList.add(newObj); + // emit new instance signal + } + obj.initialize(mobj); + //emit new instance signal + instList.add(obj); + + instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + + // Check if there are any gaps between the requested instance ID and the ones in the list, + // if any then create the missing instances. + for (int instId = instList.size(); instId < obj.getInstID(); ++instId) + { + UAVDataObject cobj = obj.clone(instId); + cobj.initialize(mobj); + instList.add(cobj); + // emit newInstance(cobj); + } + // Finally, initialize the actual object instance + obj.initialize(mobj); + // Add the actual object instance in the list + instList.add(obj); + //emit newInstance(obj); + return true; + } + + } + + // If this point is reached then this is the first time this object type (ID) is added in the list + // create a new list of the instances, add in the object collection and create the object's metaobject + // Create metaobject + String mname = obj.getName(); + mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); + // Initialize object + obj.initialize(0, mobj); + // Add to list + addObject(obj); + addObject(mobj); + return true; + } + + void addObject(UAVObject obj) + { + // Add to list + List ls = new ArrayList(); + ls.add(obj); + objects.add(ls); + //emit newObject(obj); + } + + /** + * Get all objects. A two dimentional QList is returned. Objects are grouped by + * instances of the same object type. + */ + List> getObjects() + { + //QMutexLocker locker(mutex); + return objects; + } + + /** + * Same as getObjects() but will only return DataObjects. + */ + List< List > getDataObjects() + { + return new ArrayList>(); + + /* QMutexLocker locker(mutex); + QList< QList > dObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVDataObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVDataObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + dObjects.append(list); + } + } + }*/ + // Done + } + + /** + * Same as getObjects() but will only return MetaObjects. + */ + List > getMetaObjects() + { + return new ArrayList< List >(); + /* + QMutexLocker locker(mutex); + QList< QList > mObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVMetaObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + mObjects.append(list); + } + } + } + // Done + return mObjects; + */ + } + + /** + * Get a specific object given its name and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(String name, int instId) + { + return getObject(name, 0, instId); + } + + /** + * Get a specific object given its object and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(int objId, int instId) + { + return getObject(null, objId, instId); + } + + /** + * Helper function for the public getObject() functions. + */ + UAVObject getObject(String name, int objId, int instId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + // Look for the requested instance ID + ListIterator iter = instList.listIterator(); + while(iter.hasNext()) { + UAVObject obj = iter.next(); + if(obj.getInstID() == instId) { + return obj; + } + } + } + } + } + + return null; + } + + /** + * Get all the instances of the object specified by name + */ + List getObjectInstances(String name) + { + return getObjectInstances(name, 0); + } + + /** + * Get all the instances of the object specified by its ID + */ + List getObjectInstances(int objId) + { + return getObjectInstances(null, objId); + } + + /** + * Helper function for the public getObjectInstances() + */ + List getObjectInstances(String name, int objId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + return instList; + } + } + } + + return null; + } + + /** + * Get the number of instances for an object given its name + */ + int getNumInstances(String name) + { + return getNumInstances(name, 0); + } + + /** + * Get the number of instances for an object given its ID + */ + int getNumInstances(int objId) + { + return getNumInstances(null, objId); + } + + /** + * Helper function for public getNumInstances + */ + int getNumInstances(String name, int objId) + { + return getObjectInstances(name,objId).size(); + } + + +} From 8d7dc0eab7f5f648396d4481320ff8a813629c42 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 01:23:10 -0600 Subject: [PATCH 193/508] Trying to get eclipse project right --- .gitignore | 9 +- androidgcs/.classpath | 7 ++ androidgcs/.project | 33 ++++++ .../.settings/org.eclipse.jdt.core.prefs | 5 + androidgcs/AndroidManifest.xml | 10 +- androidgcs/bin/OpieMobi.apk | Bin 148198 -> 0 bytes androidgcs/bin/classes.dex | Bin 12640 -> 0 bytes .../ObjBrowserExpandableListAdapter.class | Bin 3092 -> 0 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 951 -> 0 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 358 -> 0 bytes .../org/openpilot/androidgcs/R$color.class | Bin 447 -> 0 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 418 -> 0 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 403 -> 0 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 449 -> 0 bytes .../org/openpilot/androidgcs/R$string.class | Bin 445 -> 0 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 627 -> 0 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 1127 -> 0 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 1440 -> 0 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 1199 -> 0 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 1333 -> 0 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 2255 -> 0 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 5422 -> 0 bytes androidgcs/bin/resources.ap_ | Bin 140460 -> 0 bytes androidgcs/default.properties | 2 +- .../gen/org/openpilot/androidgcs/R.java | 31 ------ androidgcs/res/drawable-hdpi/icon.png | Bin 48558 -> 4147 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 48558 -> 1723 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 48558 -> 2574 bytes androidgcs/res/layout/objectbrowser.xml | 8 -- androidgcs/res/values/strings.xml | 6 +- .../ObjBrowserExpandableListAdapter.java | 99 ------------------ .../openpilot/androidgcs/ObjectBrowser.java | 21 ---- .../org/openpilot/uavtalk/UAVMetaObject.java | 12 +-- 33 files changed, 61 insertions(+), 182 deletions(-) create mode 100644 androidgcs/.classpath create mode 100644 androidgcs/.project create mode 100644 androidgcs/.settings/org.eclipse.jdt.core.prefs delete mode 100644 androidgcs/bin/OpieMobi.apk delete mode 100644 androidgcs/bin/classes.dex delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class delete mode 100644 androidgcs/bin/resources.ap_ delete mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java delete mode 100644 androidgcs/res/layout/objectbrowser.xml delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/.gitignore b/.gitignore index dc058313d..c9478a9c1 100644 --- a/.gitignore +++ b/.gitignore @@ -64,13 +64,16 @@ ground/uavobjgenerator/uavobjgenerator.pro.user ground/uavobjects/uavobjects.pro.user ground/ground.pro.user -# Ignore GNU global tags files GPATH GRTAGS GSYMS GTAGS -/.cproject -/.project plane quad + +# Ignore auto generated java files +androidgcs/bin/ +androidgcs/gen/ +/.cproject +/.project diff --git a/androidgcs/.classpath b/androidgcs/.classpath new file mode 100644 index 000000000..609aa00eb --- /dev/null +++ b/androidgcs/.classpath @@ -0,0 +1,7 @@ + + + + + + + diff --git a/androidgcs/.project b/androidgcs/.project new file mode 100644 index 000000000..c607dd2bd --- /dev/null +++ b/androidgcs/.project @@ -0,0 +1,33 @@ + + + androidgcs + + + + + + com.android.ide.eclipse.adt.ResourceManagerBuilder + + + + + com.android.ide.eclipse.adt.PreCompilerBuilder + + + + + org.eclipse.jdt.core.javabuilder + + + + + com.android.ide.eclipse.adt.ApkBuilder + + + + + + com.android.ide.eclipse.adt.AndroidNature + org.eclipse.jdt.core.javanature + + diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs new file mode 100644 index 000000000..f3fe4d6d6 --- /dev/null +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -0,0 +1,5 @@ +#Tue Mar 01 01:16:25 CST 2011 +eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 +org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 83d19e96c..7a96a6600 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -3,16 +3,10 @@ package="org.openpilot.androidgcs" android:versionCode="1" android:versionName="1.0"> - + - - - - - - + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk deleted file mode 100644 index 87a15c5e83805a3bb48265a78f9bd9154813cd35..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class deleted file mode 100644 index 306bc08c9eca5d510d01792bc7011e1ef8b75cc0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class deleted file mode 100644 index f69a8e17560897ad1adaae18fd15a3f75ac850a4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class deleted file mode 100644 index 43d486e461eb753c8772c3c239c81b3a83a13216..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class deleted file mode 100644 index d473cb81c8c6db44be5035f5848de2cfe8504c66..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class deleted file mode 100644 index 95af7d70364676903cbaee10411198d19f52394b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class deleted file mode 100644 index 7234b135ec1e4b601e8d271c48caf5fa07bd47ba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class deleted file mode 100644 index 5e520fa0eb6d9ad0cf329fa2572250588a3e365e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class deleted file mode 100644 index 5e228155303a29cd063056a485473fdd564000c7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class deleted file mode 100644 index f4a6dd7e4e5820644e459a4aa5652e5f2a69beba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ deleted file mode 100644 index 2452fd26f12793bb5445461ce339266070961506..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u diff --git a/androidgcs/default.properties b/androidgcs/default.properties index e2e8061f2..46769a720 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-8 +target=android-7 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java deleted file mode 100644 index 31e90ffd1..000000000 --- a/androidgcs/gen/org/openpilot/androidgcs/R.java +++ /dev/null @@ -1,31 +0,0 @@ -/* AUTO-GENERATED FILE. DO NOT MODIFY. - * - * This class was automatically generated by the - * aapt tool from the resource data it found. It - * should not be modified by hand. - */ - -package org.openpilot.androidgcs; - -public final class R { - public static final class attr { - } - public static final class color { - public static final int all_black=0x7f050001; - public static final int all_white=0x7f050000; - } - public static final class drawable { - public static final int icon=0x7f020000; - } - public static final class id { - public static final int objects=0x7f060000; - } - public static final class layout { - public static final int main=0x7f030000; - public static final int objectbrowser=0x7f030001; - } - public static final class string { - public static final int app_name=0x7f040001; - public static final int hello=0x7f040000; - } -} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..8074c4c571b8cd19e27f4ee5545df367420686d7 100644 GIT binary patch literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926
r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..1095584ec21f71cd0afc9e0993aa2209671b590c 100644 GIT binary patch literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..a07c69fa5a0f4da5d5efe96eea12a543154dbab6 100644 GIT binary patch literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(hvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml deleted file mode 100644 index 02a3f5dd6..000000000 --- a/androidgcs/res/layout/objectbrowser.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index eba6becf8..0d9f93bc2 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,7 +1,5 @@ - OpenPilot Android GCS - OpieMobi - #FFFFFF - #000000 + Hello World! + OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java deleted file mode 100644 index 190668d80..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java +++ /dev/null @@ -1,99 +0,0 @@ -/** - * - */ -package org.openpilot.androidgcs; - -import android.widget.AbsListView; -import android.widget.TextView; -import android.content.Context; -import android.view.Gravity; -import android.view.View; -import android.view.ViewGroup; -import android.widget.BaseExpandableListAdapter; - -/** - * @author jcotton81 - * - */ -public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { - - // Sample data set. children[i] contains the children (String[]) for - // groups[i]. - private String[] groups = { "Parent1", "Parent2", "Parent3" }; - private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; - - private Context context; - - public ObjBrowserExpandableListAdapter(Context context) { - this.context = context; - } - - public Object getChild(int groupPosition, int childPosition) { - return children[groupPosition][childPosition]; - } - - public long getChildId(int groupPosition, int childPosition) { - return childPosition; - } - - public int getChildrenCount(int groupPosition) { - int i = 0; - try { - i = children[groupPosition].length; - - } catch (Exception e) { - } - - return i; - } - - public TextView getGenericView() { - // Layout parameters for the ExpandableListView - AbsListView.LayoutParams lp = new AbsListView.LayoutParams( - ViewGroup.LayoutParams.FILL_PARENT, 64); - - TextView textView = new TextView(context); - textView.setLayoutParams(lp); - // Center the text vertically - textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); - // Set the text starting position - textView.setPadding(36, 0, 0, 0); - return textView; - } - - public View getChildView(int groupPosition, int childPosition, - boolean isLastChild, View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getChild(groupPosition, childPosition).toString()); - return textView; - } - - public Object getGroup(int groupPosition) { - return groups[groupPosition]; - } - - public int getGroupCount() { - return groups.length; - } - - public long getGroupId(int groupPosition) { - return groupPosition; - } - - public View getGroupView(int groupPosition, boolean isExpanded, - View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getGroup(groupPosition).toString()); - return textView; - } - - public boolean isChildSelectable(int groupPosition, int childPosition) { - return true; - } - - public boolean hasStableIds() { - return true; - } - - -} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java deleted file mode 100644 index 19e9b2812..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ /dev/null @@ -1,21 +0,0 @@ -package org.openpilot.androidgcs; - -import android.app.Activity; -import android.os.Bundle; - -import android.widget.*; - -public class ObjectBrowser extends Activity { - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - - setContentView(R.layout.objectbrowser); - ExpandableListAdapter mAdapter; - ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); - mAdapter = new ObjBrowserExpandableListAdapter(this); - epView.setAdapter(mAdapter); - - } -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index a1e5773b9..e5197b02e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,13 +2,11 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, Boolean isSingleInst, String name) { - super(objID, isSingleInst, name); - // TODO Auto-generated constructor stub - } - - public UAVMetaObject(int objID, String mname, UAVDataObject obj) { - // TODO Auto-generated constructor stub + private UAVDataObject parent; + + public UAVMetaObject(int objID, String mname, UAVDataObject parent) { + super(objID, true, mname); + this.parent = parent; } @Override From 7ab3f5b47eebe4a1f6ee3396b4cdbaab4dd793b8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 22:27:58 -0600 Subject: [PATCH 194/508] Update the object template to be more consistent with ground code --- .../templates/uavobjecttemplate.java | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 285ad03aa..13eeeb724 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -29,30 +29,31 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectMetaData; -import org.openpilot.uavtalk.UAVObjectFieldDescription; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; + /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVObject{ +public class $(NAME) extends UAVDataObject{ $(FIELDSINIT) public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVObjectMetaData.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObjectMetaData.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObjectMetaData.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObjectMetaData.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObjectMetaData.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObjectMetaData.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObjectMetaData.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -65,7 +66,7 @@ $(FIELDSINIT) return "$(NAME)"; } - public String getObjDescription() { + public String getDescription() { return "$(DESCRIPTION)"; } From 0abd2ee6719138e3dc36d2ee1117d935c877acdd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 2 Mar 2011 20:23:27 -0600 Subject: [PATCH 195/508] Continuing to work on the java code to be more consistent with GCS code --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 34 +++++++++++--- .../org/openpilot/uavtalk/UAVMetaObject.java | 47 +++++++++++++++---- .../src/org/openpilot/uavtalk/UAVObject.java | 36 ++++++++++---- .../templates/uavobjecttemplate.java | 30 ++++++++---- 5 files changed, 117 insertions(+), 31 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 609aa00eb..b24a2abf5 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -3,5 +3,6 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 12a4263c0..a2e6acf9e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -2,17 +2,20 @@ package org.openpilot.uavtalk; public abstract class UAVDataObject extends UAVObject { + /** + * @brief Constructor for UAVDataObject + * @param objID the object id to be created + * @param isSingleInst + * @param isSet + * @param name + */ public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); } - public void initialize(int instID, UAVMetaObject mobj) { - - } + public abstract void initialize(int instID, UAVMetaObject mobj); - public void initialize(UAVMetaObject mobj) { - - } + public abstract void initialize(UAVMetaObject mobj); Boolean isSettings() { return null; @@ -22,6 +25,23 @@ public abstract class UAVDataObject extends UAVObject { return null; } - public abstract UAVDataObject clone(int instID); + public UAVDataObject clone(int instID) { + try { + return (UAVDataObject) super.clone(); + } catch (CloneNotSupportedException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + return null; + } + +public: + static int OBJID = $(OBJIDHEX); + static String NAME; + static String DESCRIPTION; + static boolean ISSINGLEINST = $(ISSINGLEINST); + static boolean ISSETTINGS = $(ISSETTINGS); + static int NUMBYTES = sizeof(DataFields); + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index e5197b02e..9c2e3b12d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,23 +2,41 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - private UAVDataObject parent; - - public UAVMetaObject(int objID, String mname, UAVDataObject parent) { - super(objID, true, mname); + public UAVMetaObject(int objID, String name, UAVDataObject parent) { + super(objID, true, name); this.parent = parent; + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + } + + UAVObject getParentObject() { + return parent; } @Override public void deserialize(byte[] arr, int offset) { // TODO Auto-generated method stub - + } @Override - public UAVMetaObject getDefaultMetadata() { - // TODO Auto-generated method stub - return null; + public Metadata getMetadata() { + return ownMetadata; + } + + @Override + public Metadata getDefaultMetadata() { + return ownMetadata; } @Override @@ -45,4 +63,17 @@ public class UAVMetaObject extends UAVObject { return null; } + + public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); + UAVObject* getParentObject(); + void setMetadata(const Metadata& mdata); + void setData(const Metadata& mdata); + Metadata getData(); + + + private UAVObject parent; + private Metadata ownMetadata; + private Metadata parentMetadata; + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index c5ffc9d21..1decf3563 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -20,11 +20,27 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY } ; - - - private Boolean isSingleInst; - private int instID; - private UAVMetaObject meta; + + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; + + final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; public UAVObject(int objID, Boolean isSingleInst, String name) { assert(objID == getObjID()); // ID is in implementation code, make sure it matches object @@ -62,9 +78,13 @@ public abstract class UAVObject { return true; } - public void setMetadata(UAVMetaObject obj) { meta = obj; } - public UAVMetaObject getMetadata() { return meta; } - public abstract UAVMetaObject getDefaultMetadata(); + public abstract void setMetadata(Metadata obj); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; /* // Unported code from QT diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 13eeeb724..fa09f782f 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -31,29 +31,34 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVDataObject{ +public class $(NAME) extends UAVDataObject { $(FIELDSINIT) + public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + } + public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -69,6 +74,15 @@ $(FIELDSINIT) public String getDescription() { return "$(DESCRIPTION)"; } +protected: + // Constants + static final int OBJID = $(OBJIDHEX); + static final String NAME; + static final String DESCRIPTION; + static final boolean ISSINGLEINST = $(ISSINGLEINST); + static final boolean ISSETTINGS = $(ISSETTINGS); + static final int NUMBYTES = sizeof(DataFields); + $(GETTERSETTER) } \ No newline at end of file From 180f87dae5131db611264e24be570c9ba1306265 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 00:06:17 -0600 Subject: [PATCH 196/508] Import of UAVObjectField object. This differs a bit from the GCS implementation in that the data is stored within the field instead of being packed back into a continugious memory region. This is because java doesn't allow casting to struct so the memory access isn't a useful feature. --- .../org/openpilot/uavtalk/UAVObjectField.java | 468 ++++++++++++++++++ 1 file changed, 468 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java new file mode 100644 index 000000000..832e7048a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -0,0 +1,468 @@ +package org.openpilot.uavtalk; + +import java.io.Serializable; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.ArrayList; +import java.util.List; + +public class UAVObjectField { + + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + + public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { + List elementNames = new ArrayList(); + // Set element names + for (int n = 0; n < numElements; ++n) + { + elementNames.add(String.valueOf(n)); + } + // Initialize + constructorInitialize(name, units, type, elementNames, options); + } + + public UAVObjectField(String name, String units, FieldType type, List elementNames, List options) { + constructorInitialize(name, units, type, elementNames, options); + } + + public void initialize(byte[] data, int dataOffset, UAVObject obj){ + this.data = data; + this.offset = dataOffset; + this.obj = obj; + clear(); + + } + + public UAVObject getObject() { + return obj; + } + + public FieldType getType() { + return type; + } + + public String getTypeAsString() { + switch (type) + { + case INT8: + return "int8"; + case INT16: + return "int16"; + case INT32: + return "int32"; + case UINT8: + return "uint8"; + case UINT16: + return "uint16"; + case UINT32: + return "uint32"; + case FLOAT32: + return "float32"; + case ENUM: + return "enum"; + case STRING: + return "string"; + default: + return ""; + } + } + + public String getName() { + return name; + } + + public String getUnits() { + return units; + } + + public int getNumElements() { + return numElements; + } + + public List getElementNames() { + return elementNames; + } + + public List getOptions() { + return options; + } + + /** + * This function copies this field from the internal storage of the parent object + * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) + * to the arm/uavtalk standard (little endian) + * @param dataOut + * @return +] + * @throws Exception */ + public int pack(ByteBuffer dataOut) throws Exception { + //QMutexLocker locker(obj->getMutex()); + // Pack each element in output buffer + dataOut.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case INT16: + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case INT32: + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case UINT8: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case UINT16: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case UINT32: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case FLOAT32: + for (int index = 0; index < numElements; ++index) + dataOut.putFloat((Float) getValue(index)); + break; + case ENUM: + List l = (List) data; + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) l.get(index)); + break; + case STRING: + // TODO: Implement strings + throw new Exception("Strings not yet implemented"); + } + // Done + return getNumBytes(); + } + + public int unpack(ByteBuffer dataIn) throws Exception { + // Unpack each element from input buffer + dataIn.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case INT16: + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case INT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case UINT8: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case UINT16: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case UINT32: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case FLOAT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Float) dataIn.getFloat(), index); + } + break; + case ENUM: + List l = (List) data; + for (int index = 0 ; index < numElements; ++index) { + l.set(index, dataIn.get(index)); + } + break; + case STRING: + throw new Exception("Strings not handled"); + } + // Done + return getNumBytes(); + } + + Object getValue() throws Exception { return getValue(0); }; + Object getValue(int index) throws Exception { +// QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + { + return null; + } + + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + return l.get(index); + } + case UINT8: + case UINT16: + case UINT32: + { + // TODO: Correctly deal with unsigned values + List l = (List) data; + return l.get(index); + } + case FLOAT32: + { + List l = (List) data; + return l.get(index); + } + case ENUM: + { + List l = (List) data; + Byte val = l.get(index); + + if(val >= options.size() || val < 0) + throw new Exception("Invalid value for" + name); + + return options.get(val); + } + case STRING: + { + throw new Exception("Shit I should do this"); + } + } + // If this point is reached then we got an invalid type + return null; + } + + public void setValue(Object data) throws Exception { setValue(data,0); } + public void setValue(Object data, int index) throws Exception { + // QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + throw new Exception("Index out of bounds"); + + // Get metadata + UAVObject.Metadata mdata = obj.getMetadata(); + // Update value if the access mode permits + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + { + ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case UINT8: + case UINT16: + case UINT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case FLOAT32: + { + List l = (List) data; + l.set(index, (Float) data); + break; + } + case ENUM: + { + byte val = (byte) options.indexOf((String) data); + if(val < 0) throw new Exception("Enumerated value not found"); + List l = (List) data; + l.set(index, val); + break; + } + case STRING: + { + throw new Exception("Sorry I haven't implemented strings yet"); + } + } + } + } + + public double getDouble() throws Exception { return getDouble(0); }; + public double getDouble(int index) throws Exception { + return Double.valueOf((Double) getValue(index)); + } + + void setDouble(double value) throws Exception { setDouble(value, 0); }; + void setDouble(double value, int index) throws Exception { + setValue(value, index); + } + + int getDataOffset() { + return offset; + } + + int getNumBytes() { + return numBytesPerElement * numElements; + } + + int getNumBytesElement() { + return numBytesPerElement; + } + + boolean isNumeric() { + switch (type) + { + case INT8: + return true; + case INT16: + return true; + case INT32: + return true; + case UINT8: + return true; + case UINT16: + return true; + case UINT32: + return true; + case FLOAT32: + return true; + case ENUM: + return false; + case STRING: + return false; + default: + return false; + } + } + + boolean isText() { + switch (type) + { + case INT8: + return false; + case INT16: + return false; + case INT32: + return false; + case UINT8: + return false; + case UINT16: + return false; + case UINT32: + return false; + case FLOAT32: + return false; + case ENUM: + return true; + case STRING: + return true; + default: + return false; + } + } + + public String toString() { + String sout = new String(); + sout += name + ": [ "; + for (int n = 0; n < numElements; ++n) + { + sout += String.valueOf(n) + " "; + } + + sout += "] " + units + "\n"; + return sout; + } + + void fieldUpdated(UAVObjectField field) { + + } + + public void clear() { + // TODO: This accesses a shared array of the parent + } + + public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + // Copy params + this.name = name; + this.units = units; + this.type = type; + this.options = options; + this.numElements = elementNames.size(); + this.offset = 0; + this.data = null; + this.obj = null; + this.elementNames = elementNames; + // Set field size + switch (type) + { + case INT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case INT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case INT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case UINT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case UINT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case UINT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case FLOAT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case ENUM: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case STRING: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + default: + numBytesPerElement = 0; + } + } + + + private String name; + private String units; + private FieldType type; + private List elementNames; + private List options; + private int numElements; + private int numBytesPerElement; + private int offset; + private Object data; + private UAVObject obj; + +} From b5e1d3bf2969fee97c756cee0f5af278a884375f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 10:22:11 -0600 Subject: [PATCH 197/508] Some changes to the object field to get it to initialze the array to be the right length --- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 75 ++++++++++++++----- 2 files changed, 56 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 1decf3563..aaf32151f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -84,7 +84,7 @@ public abstract class UAVObject { private Boolean isSingleInst; private int instID; - private UAVMetaObject meta; + private Metadata meta; /* // Unported code from QT diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 832e7048a..d09008cbe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -25,10 +25,8 @@ public class UAVObjectField { constructorInitialize(name, units, type, elementNames, options); } - public void initialize(byte[] data, int dataOffset, UAVObject obj){ - this.data = data; - this.offset = dataOffset; - this.obj = obj; + public void initialize(UAVObject obj){ + this.obj = obj; clear(); } @@ -258,10 +256,13 @@ public class UAVObjectField { if ( index >= numElements ) throw new Exception("Index out of bounds"); + System.out.println(data.toString()); + System.out.println(this.data.toString()); + // Get metadata - UAVObject.Metadata mdata = obj.getMetadata(); + //UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) @@ -270,7 +271,7 @@ public class UAVObjectField { case INT16: case INT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } @@ -278,13 +279,13 @@ public class UAVObjectField { case UINT16: case UINT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } case FLOAT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Float) data); break; } @@ -292,7 +293,7 @@ public class UAVObjectField { { byte val = (byte) options.indexOf((String) data); if(val < 0) throw new Exception("Enumerated value not found"); - List l = (List) data; + List l = (List) this.data; l.set(index, val); break; } @@ -395,7 +396,37 @@ public class UAVObjectField { } public void clear() { - // TODO: This accesses a shared array of the parent + switch (type) + { + case INT8: + case INT16: + case INT32: + case UINT8: + case UINT16: + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add(0); + } + break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte)0); + } + break; + case STRING: + // TODO: Add string + break; + default: + numBytesPerElement = 0; + } } public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { @@ -410,47 +441,51 @@ public class UAVObjectField { this.obj = null; this.elementNames = elementNames; // Set field size + System.out.println("Initializing: type " + type + this.numElements); + switch (type) { case INT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case STRING: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; default: numBytesPerElement = 0; } + clear(); + System.out.println("Initialized: " + this.data.toString()); } From 1c2eb1bf222906c5c70997c5d69ee4d9ccad9925 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 5 Mar 2011 12:29:48 -0600 Subject: [PATCH 198/508] More updates to UAVObject and Field for android app --- .../src/org/openpilot/uavtalk/UAVObject.java | 598 ++++++++++++++---- .../org/openpilot/uavtalk/UAVObjectField.java | 3 +- 2 files changed, 475 insertions(+), 126 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index aaf32151f..f987a03a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,137 +1,487 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.List; +import java.util.ListIterator; + public abstract class UAVObject { - - - /** - * Object update mode - */ - public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ - UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; - /** - * Access mode - */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; - - /** - * Access mode - */ - public enum Acked{ - FALSE, - TRUE - } ; - - final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; - public UAVObject(int objID, Boolean isSingleInst, String name) { - assert(objID == getObjID()); // ID is in implementation code, make sure it matches object - assert(name.equals(getName())); - this.isSingleInst = isSingleInst; - meta = getDefaultMetadata(); - }; - - public void initialize(int instID) { - this.instID = instID; - } - - public int getInstID() { return instID; } - public Boolean isSingleInstance() { return isSingleInst; } - public String getName() { return getObjName(); } // matching QT API to the current autogen code - - public abstract int getObjID(); - public abstract String getDescription(); - public abstract String getObjName(); - - int getNumBytes() { - return serialize().length; - } + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; - // The name of the serializer and deserialize from the autogenerated code - public abstract byte[] serialize(); - public abstract void deserialize(byte[] arr,int offset); - - byte [] pack() { - return serialize(); - } - - Boolean unpack(byte [] data) { - deserialize(data, 0); - return true; - } - - public abstract void setMetadata(Metadata obj); - public abstract Metadata getMetadata(); - public abstract Metadata getDefaultMetadata(); + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; - private Boolean isSingleInst; - private int instID; - private Metadata meta; + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; - /* - // Unported code from QT - bool save(); - bool save(QFile& file); - bool load(); - bool load(QFile& file); - virtual void setMetadata(const Metadata& mdata) = 0; - virtual Metadata getMetadata() = 0; - virtual Metadata getDefaultMetadata() = 0; - void requestUpdate(); - void updated(); - void lock(); - void lock(int timeoutMs); - void unlock(); - QMutex* getMutex(); - qint32 getNumFields(); - QList getFields(); - UAVObjectField* getField(const QString& name); - QString toString(); - QString toStringBrief(); - QString toStringData(); - void emitTransactionCompleted(bool success); + protected final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; - signals: - void objectUpdated(UAVObject* obj); - void objectUpdatedAuto(UAVObject* obj); - void objectUpdatedManual(UAVObject* obj); - void objectUnpacked(UAVObject* obj); - void updateRequested(UAVObject* obj); - void transactionCompleted(UAVObject* obj, bool success); + public UAVObject(int objID, Boolean isSingleInst, String name) { + this.objID = objID; + this.instID = 0; + this.isSingleInst = isSingleInst; + this.name = name; + // this.mutex = new QMutex(QMutex::Recursive); + }; - private slots: - void fieldUpdated(UAVObjectField* field); + public void initialize(int instID) { + //QMutexLocker locker(mutex); + this.instID = instID; + } - protected: - quint32 objID; - quint32 instID; - bool isSingleInst; - QString name; - QString description; - quint32 numBytes; - QMutex* mutex; - quint8* data; - QList fields; + /** + * Initialize objects' data fields + * @param fields List of fields held by the object + * @param data Pointer to that actual object data, this is needed by the fields to access the data + * @param numBytes Number of bytes in the object (total, including all fields) + * @throws Exception When unable to unpack a field + */ + public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception + { + // TODO: QMutexLocker locker(mutex); + this.numBytes = numBytes; + this.data = data; + this.fields = fields; + // Initialize fields + for (int n = 0; n < fields.size(); ++n) + { + fields.get(n).initialize(this); + } + unpack(data); + } - void initializeFields(QList& fields, quint8* data, quint32 numBytes); - void setDescription(const QString& description); - */ + /** + * Get the object ID + */ + public int getObjID() + { + return objID; + } + + /** + * Get the instance ID + */ + public int getInstID() + { + return instID; + } + + /** + * Returns true if this is a single instance object + */ + public boolean isSingleInstance() + { + return isSingleInst; + } + + /** + * Get the name of the object + */ + public String getName() + { + return name; + } + + /** + * Get the description of the object + * @return The description of the object + */ + public String getDescription() + { + return description; + } + + /** + * Set the description of the object + * @param The description of the object + * @return + */ + public void setDescription(String description) + { + this.description = description; + } + + + /** + * Get the total number of bytes of the object's data + */ + public int getNumBytes() + { + return numBytes; + } + + // /** + // * Request that this object is updated with the latest values from the autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ + // + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ + // + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ + // + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } + + /** + * Get the number of fields held by this object + */ + public int getNumFields() + { + //QMutexLocker locker(mutex); + return fields.size(); + } + + /** + * Get the object's fields + */ + public List getFields() + { + //QMutexLocker locker(mutex); + return fields; + } + + /** + * Get a specific field + * @throws Exception + * @returns The field or NULL if not found + */ + public UAVObjectField getField(String name) throws Exception + { + //QMutexLocker locker(mutex); + // Look for field + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + if(field.getName().equals(name)) + return field; + } + throw new Exception("Field not found"); + } + + /** + * Pack the object data into a byte array + * @param dataOut ByteBuffer to receive the data. + * @throws Exception + * @returns The number of bytes copied + * @note The array must already have enough space allocated for the object + */ + public int pack(ByteBuffer dataOut) throws Exception + { + // QMutexLocker locker(mutex); + if(dataOut.remaining() < getNumBytes()) + throw new Exception("Not enough bytes in ByteBuffer to pack object"); + int numBytes = 0; + + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.pack(dataOut); + } + return numBytes; + } + + /** + * Unpack the object data from a byte array + * @param dataIn The ByteBuffer to pull data from + * @throws Exception + * @returns The number of bytes copied + */ + public int unpack(ByteBuffer dataIn) throws Exception + { + // QMutexLocker locker(mutex); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.unpack(dataIn); + } + return numBytes; + // TODO: Callbacks + //emit objectUnpacked(this); // trigger object updated event + //emit objectUpdated(this); + } + + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } + // + // // Write object + // if ( !save(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } + // + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } + // + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } + // + // // Done + // return true; + // } + // + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } + // + // // Load object + // if ( !load(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } + // + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } + // + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); + // + // // Done + // return true; + // } + + /** + * Return a string with the object information + */ + @Override + public String toString() + { + return toStringBrief() + toStringData(); + } + + /** + * Return a string with the object information (only the header) + */ + public String toStringBrief() + { + return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", + getName(), + getObjID(), + getInstID(), + getNumBytes(), + isSingleInstance()); + } + + /** + * Return a string with the object information (only the data) + */ + public String toStringData() + { + String s = new String(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + s += field.toString(); + } + return s; + } + + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } + + /** + * Java specific functions + */ + public UAVObject clone() { + return (UAVObject) clone(); + } + /** + * Abstract functions + */ + public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + public abstract UAVDataObject clone(int instID); + protected abstract void setDefaultFieldValues(); + + /** + * Private data for the object, common to all + */ + protected int objID; + protected int instID; + protected boolean isSingleInst; + protected String name; + protected String description; + protected int numBytes; + // TODO: QMutex* mutex; + protected ByteBuffer data; + protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d09008cbe..c7c774199 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,7 @@ public class UAVObjectField { * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) * to the arm/uavtalk standard (little endian) * @param dataOut - * @return -] + * @return the number of bytes added * @throws Exception */ public int pack(ByteBuffer dataOut) throws Exception { //QMutexLocker locker(obj->getMutex()); From a2e93f19716524d9237037f354472a32888827b2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:20 -0600 Subject: [PATCH 199/508] More work on the java UAVObject implementation --- .../org/openpilot/uavtalk/UAVDataObject.java | 93 ++- .../org/openpilot/uavtalk/UAVMetaObject.java | 140 +++-- .../src/org/openpilot/uavtalk/UAVObject.java | 581 +++++++++--------- .../org/openpilot/uavtalk/UAVObjectField.java | 35 +- .../openpilot/uavtalk/UAVObjectManager.java | 30 +- 5 files changed, 497 insertions(+), 382 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index a2e6acf9e..f0a2248f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,39 +9,78 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { super(objID, isSingleInst, name); + mobj = null; + this.isSet = isSet; } - - public abstract void initialize(int instID, UAVMetaObject mobj); - - public abstract void initialize(UAVMetaObject mobj); - - Boolean isSettings() { - return null; + /** + * Initialize instance ID and assign a metaobject + */ + public void initialize(int instID, UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + super.initialize(instID); + } + + /** + * Assign a metaobject + */ + public void initialize(UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + } + + /** + * Returns true if this is a data object holding module settings + */ + public boolean isSettings() + { + return isSet; + } + + /** + * Set the object's metadata + */ + public void setMetadata(Metadata mdata) + { + if ( mobj != null ) + { + mobj.setData(mdata); + } + } + + /** + * Get the object's metadata + */ + public Metadata getMetadata() + { + if ( mobj != null) + { + return mobj.getData(); + } + else + { + return getDefaultMetadata(); + } + } + + /** + * Get the metaobject + */ + public UAVMetaObject getMetaObject() + { + return mobj; } - - UAVMetaObject getMetaObject() { - return null; - } + // TODO: Make abstract public UAVDataObject clone(int instID) { - try { - return (UAVDataObject) super.clone(); - } catch (CloneNotSupportedException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - return null; + return (UAVDataObject) super.clone(); } -public: - static int OBJID = $(OBJIDHEX); - static String NAME; - static String DESCRIPTION; - static boolean ISSINGLEINST = $(ISSINGLEINST); - static boolean ISSETTINGS = $(ISSETTINGS); - static int NUMBYTES = sizeof(DataFields); - + private UAVMetaObject mobj; + private boolean isSet; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 9c2e3b12d..70e661d46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -1,76 +1,116 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, String name, UAVDataObject parent) { + public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; - - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.loggingUpdatePeriod = 0; - + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + // Setup fields + List boolEnum = new ArrayList(); + boolEnum.add("False"); + boolEnum.add("True"); + + List updateModeEnum = new ArrayList(); + updateModeEnum.add("Periodic"); + updateModeEnum.add("On Change"); + updateModeEnum.add("Manual"); + updateModeEnum.add("Never"); + + List accessModeEnum = new ArrayList(); + accessModeEnum.add("Read/Write"); + accessModeEnum.add("Read Only"); + + List fields = new ArrayList(); + fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + + // Initialize parent + super.initialize(0); + super.initializeFields(fields, ByteBuffer.allocate(10), 10); + + // Setup metadata of parent + parentMetadata = parent.getDefaultMetadata(); } - UAVObject getParentObject() { + /** + * Get the parent object + */ + public UAVObject getParentObject() + { return parent; } - @Override - public void deserialize(byte[] arr, int offset) { - // TODO Auto-generated method stub - + /** + * Set the metadata of the metaobject, this function will + * do nothing since metaobjects have read-only metadata. + */ + public void setMetadata(Metadata mdata) + { + return; // can not update metaobject's metadata } - @Override - public Metadata getMetadata() { + /** + * Get the metadata of the metaobject + */ + public Metadata getMetadata() + { return ownMetadata; } - @Override - public Metadata getDefaultMetadata() { - return ownMetadata; + /** + * Get the default metadata + */ + public Metadata getDefaultMetadata() + { + return ownMetadata; } - @Override - public String getDescription() { - // TODO Auto-generated method stub - return null; + /** + * Set the metadata held by the metaobject + */ + public void setData(Metadata mdata) + { + //QMutexLocker locker(mutex); + parentMetadata = mdata; + // TODO: Callbacks + // emit objectUpdatedAuto(this); // trigger object updated event + // emit objectUpdated(this); } - @Override - public int getObjID() { - // TODO Auto-generated method stub - return 0; + /** + * Get the metadata held by the metaobject + */ + public Metadata getData() + { +// QMutexLocker locker(mutex); + return parentMetadata; } - @Override - public String getObjName() { - // TODO Auto-generated method stub - return null; - } - @Override - public byte[] serialize() { - // TODO Auto-generated method stub - return null; - } - - - public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); - UAVObject* getParentObject(); - void setMetadata(const Metadata& mdata); - void setData(const Metadata& mdata); - Metadata getData(); - - private UAVObject parent; private Metadata ownMetadata; private Metadata parentMetadata; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index f987a03a9..926440805 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -6,241 +6,274 @@ import java.util.ListIterator; public abstract class UAVObject { - /** * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_PERIODIC, /** + * Automatically update object at periodic + * intervals + */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; + UPDATEMODE_MANUAL, /** + * Manually update object, by calling the updated() + * function + */ + UPDATEMODE_NEVER + /** Object is never updated */ + }; /** * Access mode */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; + public enum AccessMode { + ACCESS_READWRITE, ACCESS_READONLY + }; /** * Access mode */ - public enum Acked{ - FALSE, - TRUE - } ; + public enum Acked { + FALSE, TRUE + }; - protected final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; + public final class Metadata { + public AccessMode flightAccess; + /** + * Defines the access level for the local flight transactions (readonly + * and readwrite) + */ + public AccessMode gcsAccess; + /** + * Defines the access level for the local GCS transactions (readonly and + * readwrite) + */ + public Acked flightTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode flightTelemetryUpdateMode; + /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; + /** + * Update period used by the autopilot (only if telemetry mode is + * PERIODIC) + */ + public Acked gcsTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode gcsTelemetryUpdateMode; + /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; + /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; + /** + * Update period used by the logging module (only if logging mode is + * PERIODIC) + */ + }; public UAVObject(int objID, Boolean isSingleInst, String name) { this.objID = objID; this.instID = 0; this.isSingleInst = isSingleInst; this.name = name; - // this.mutex = new QMutex(QMutex::Recursive); + // this.mutex = new QMutex(QMutex::Recursive); }; public void initialize(int instID) { - //QMutexLocker locker(mutex); + // QMutexLocker locker(mutex); this.instID = instID; } /** * Initialize objects' data fields - * @param fields List of fields held by the object - * @param data Pointer to that actual object data, this is needed by the fields to access the data - * @param numBytes Number of bytes in the object (total, including all fields) - * @throws Exception When unable to unpack a field + * + * @param fields + * List of fields held by the object + * @param data + * Pointer to that actual object data, this is needed by the + * fields to access the data + * @param numBytes + * Number of bytes in the object (total, including all fields) + * @throws Exception + * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception - { - // TODO: QMutexLocker locker(mutex); + public void initializeFields(List fields, ByteBuffer data, + int numBytes) throws Exception { + // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; - this.data = data; +// this.data = data; this.fields = fields; // Initialize fields - for (int n = 0; n < fields.size(); ++n) - { + for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } - unpack(data); +// unpack(data); } /** * Get the object ID */ - public int getObjID() - { + public int getObjID() { return objID; } /** * Get the instance ID */ - public int getInstID() - { + public int getInstID() { return instID; } /** * Returns true if this is a single instance object */ - public boolean isSingleInstance() - { + public boolean isSingleInstance() { return isSingleInst; } /** * Get the name of the object */ - public String getName() - { + public String getName() { return name; } /** * Get the description of the object + * * @return The description of the object */ - public String getDescription() - { + public String getDescription() { return description; } /** * Set the description of the object - * @param The description of the object - * @return + * + * @param The + * description of the object + * @return */ - public void setDescription(String description) - { + public void setDescription(String description) { this.description = description; } - /** * Get the total number of bytes of the object's data */ - public int getNumBytes() - { + public int getNumBytes() { return numBytes; } - // /** - // * Request that this object is updated with the latest values from the autopilot - // */ - // /* void UAVObject::requestUpdate() - // { - // emit updateRequested(this); - // } */ + // /** + // * Request that this object is updated with the latest values from the + // autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ // - // /** - // * Signal that the object has been updated - // */ - // /* void UAVObject::updated() - // { - // emit objectUpdatedManual(this); - // emit objectUpdated(this); - // } */ + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock() - // { - // mutex->lock(); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock(int timeoutMs) - // { - // mutex->tryLock(timeoutMs); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ // - // /** - // * Unlock mutex of this object - // */ - // /* void UAVObject::unlock() - // { - // mutex->unlock(); - // } */ + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ // - // /** - // * Get object's mutex - // */ - // QMutex* UAVObject::getMutex() - // { - // return mutex; - // } + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } /** * Get the number of fields held by this object */ - public int getNumFields() - { - //QMutexLocker locker(mutex); + public int getNumFields() { + // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() - { - //QMutexLocker locker(mutex); + public List getFields() { + // QMutexLocker locker(mutex); return fields; } /** * Get a specific field - * @throws Exception + * + * @throws Exception * @returns The field or NULL if not found */ - public UAVObjectField getField(String name) throws Exception - { - //QMutexLocker locker(mutex); + public UAVObjectField getField(String name) { + // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); - if(field.getName().equals(name)) + if (field.getName().equals(name)) return field; } - throw new Exception("Field not found"); + //throw new Exception("Field not found"); + return null; } /** * Pack the object data into a byte array - * @param dataOut ByteBuffer to receive the data. - * @throws Exception + * + * @param dataOut + * ByteBuffer to receive the data. + * @throws Exception * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception - { + public int pack(ByteBuffer dataOut) throws Exception { // QMutexLocker locker(mutex); - if(dataOut.remaining() < getNumBytes()) + if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); numBytes += field.pack(dataOut); } @@ -249,232 +282,232 @@ public abstract class UAVObject { /** * Unpack the object data from a byte array - * @param dataIn The ByteBuffer to pull data from - * @throws Exception + * + * @param dataIn + * The ByteBuffer to pull data from + * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception - { + public int unpack(ByteBuffer dataIn) throws Exception { + if( dataIn == null ) + return 0; + System.out.println( dataIn.toString() ); // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); + System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; // TODO: Callbacks - //emit objectUnpacked(this); // trigger object updated event - //emit objectUpdated(this); + // emit objectUnpacked(this); // trigger object updated event + // emit objectUpdated(this); } - // /** - // * Save the object data to the file. - // * The file will be created in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save() - // { - // QMutexLocker locker(mutex); + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::WriteOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } // - // // Write object - // if ( !save(file) ) - // { - // return false; - // } + // // Write object + // if ( !save(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Save the object data to the file. - // * The file is expected to be already open for writting. - // * The data will be appended and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Write the object ID - // qToLittleEndian(objID, tmpId); - // if ( file.write((const char*)tmpId, 4) == -1 ) - // { - // return false; - // } + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } // - // // Write the instance ID - // if (!isSingleInst) - // { - // qToLittleEndian(instID, tmpId); - // if ( file.write((const char*)tmpId, 2) == -1 ) - // { - // return false; - // } - // } + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } // - // // Write the data - // pack(buffer); - // if ( file.write((const char*)buffer, numBytes) == -1 ) - // { - // return false; - // } + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } // - // // Done - // return true; - // } + // // Done + // return true; + // } // - // /** - // * Load the object data from a file. - // * The file will be openned in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load() - // { - // QMutexLocker locker(mutex); + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::ReadOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } // - // // Load object - // if ( !load(file) ) - // { - // return false; - // } + // // Load object + // if ( !load(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Load the object data from file. - // * The file is expected to be already open for reading. - // * The data will be read and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Read the object ID - // if ( file.read((char*)tmpId, 4) != 4 ) - // { - // return false; - // } + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != objID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } // - // // Read the instance ID - // if ( file.read((char*)tmpId, 2) != 2 ) - // { - // return false; - // } + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != instID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } // - // // Read and unpack the data - // if ( file.read((char*)buffer, numBytes) != numBytes ) - // { - // return false; - // } - // unpack(buffer); + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); // - // // Done - // return true; - // } + // // Done + // return true; + // } /** * Return a string with the object information */ @Override - public String toString() - { + public String toString() { return toStringBrief() + toStringData(); } /** * Return a string with the object information (only the header) */ - public String toStringBrief() - { - return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", - getName(), - getObjID(), - getInstID(), - getNumBytes(), - isSingleInstance()); + public String toStringBrief() { + return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; + // getName(), getObjID(), getInstID(), getNumBytes(), + // isSingleInstance()); } /** * Return a string with the object information (only the data) */ - public String toStringData() - { + public String toStringData() { String s = new String(); ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); s += field.toString(); } return s; } - // /** - // * Emit the transactionCompleted event (used by the UAVTalk plugin) - // */ - // void UAVObject::emitTransactionCompleted(bool success) - // { - // emit transactionCompleted(this, success); - // } + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } - /** + /** * Java specific functions */ public UAVObject clone() { return (UAVObject) clone(); } + /** * Abstract functions */ public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); - public abstract UAVDataObject clone(int instID); - protected abstract void setDefaultFieldValues(); /** * Private data for the object, common to all - */ + */ protected int objID; protected int instID; protected boolean isSingleInst; @@ -482,6 +515,6 @@ public abstract class UAVObject { protected String description; protected int numBytes; // TODO: QMutex* mutex; - protected ByteBuffer data; +// protected ByteBuffer data; protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c7c774199..b37c992fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -248,34 +248,37 @@ public class UAVObjectField { return null; } - public void setValue(Object data) throws Exception { setValue(data,0); } - public void setValue(Object data, int index) throws Exception { + public void setValue(Object data) { setValue(data,0); } + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) - throw new Exception("Index out of bounds"); + //throw new Exception("Index out of bounds"); System.out.println(data.toString()); System.out.println(this.data.toString()); // Get metadata - //UAVObject.Metadata mdata = obj.getMetadata(); + UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { - ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) { case INT8: + data = new Integer((Byte) data); case INT16: + data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,(Integer) data); break; } case UINT8: + data = new Integer((Byte) data); case UINT16: + data = new Integer((Short) data); case UINT32: { List l = (List) this.data; @@ -291,14 +294,14 @@ public class UAVObjectField { case ENUM: { byte val = (byte) options.indexOf((String) data); - if(val < 0) throw new Exception("Enumerated value not found"); + //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); break; } case STRING: { - throw new Exception("Sorry I haven't implemented strings yet"); + //throw new Exception("Sorry I haven't implemented strings yet"); } } } @@ -309,24 +312,24 @@ public class UAVObjectField { return Double.valueOf((Double) getValue(index)); } - void setDouble(double value) throws Exception { setDouble(value, 0); }; - void setDouble(double value, int index) throws Exception { + public void setDouble(double value) throws Exception { setDouble(value, 0); }; + public void setDouble(double value, int index) throws Exception { setValue(value, index); } - int getDataOffset() { + public int getDataOffset() { return offset; } - int getNumBytes() { + public int getNumBytes() { return numBytesPerElement * numElements; } - int getNumBytesElement() { + public int getNumBytesElement() { return numBytesPerElement; } - boolean isNumeric() { + public boolean isNumeric() { switch (type) { case INT8: @@ -352,7 +355,7 @@ public class UAVObjectField { } } - boolean isText() { + public boolean isText() { switch (type) { case INT8: diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 3091595f0..d75b14b85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -21,8 +21,9 @@ public class UAVObjectManager { * A new instance can be created directly by instantiating a new object or by calling clone() of * an existing object. The object will be registered and will be properly initialized so that it can accept * updates. + * @throws Exception */ - Boolean registerObject(UAVDataObject obj) + public boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -126,7 +127,7 @@ public class UAVObjectManager { return true; } - void addObject(UAVObject obj) + public void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -139,7 +140,7 @@ public class UAVObjectManager { * Get all objects. A two dimentional QList is returned. Objects are grouped by * instances of the same object type. */ - List> getObjects() + public List> getObjects() { //QMutexLocker locker(mutex); return objects; @@ -148,7 +149,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - List< List > getDataObjects() + public List< List > getDataObjects() { return new ArrayList>(); @@ -186,7 +187,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return MetaObjects. */ - List > getMetaObjects() + public List > getMetaObjects() { return new ArrayList< List >(); /* @@ -227,7 +228,7 @@ public class UAVObjectManager { * Get a specific object given its name and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(String name, int instId) + public UAVObject getObject(String name, int instId) { return getObject(name, 0, instId); } @@ -236,7 +237,7 @@ public class UAVObjectManager { * Get a specific object given its object and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(int objId, int instId) + public UAVObject getObject(int objId, int instId) { return getObject(null, objId, instId); } @@ -244,7 +245,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - UAVObject getObject(String name, int objId, int instId) + public UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -271,7 +272,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by name */ - List getObjectInstances(String name) + public List getObjectInstances(String name) { return getObjectInstances(name, 0); } @@ -279,7 +280,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by its ID */ - List getObjectInstances(int objId) + public List getObjectInstances(int objId) { return getObjectInstances(null, objId); } @@ -287,7 +288,7 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - List getObjectInstances(String name, int objId) + public List getObjectInstances(String name, int objId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -307,7 +308,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its name */ - int getNumInstances(String name) + public int getNumInstances(String name) { return getNumInstances(name, 0); } @@ -315,7 +316,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its ID */ - int getNumInstances(int objId) + public int getNumInstances(int objId) { return getNumInstances(null, objId); } @@ -323,10 +324,9 @@ public class UAVObjectManager { /** * Helper function for public getNumInstances */ - int getNumInstances(String name, int objId) + public int getNumInstances(String name, int objId) { return getObjectInstances(name,objId).size(); } - } From a9066494c76e87151b9bd1cccd808f7a2ae28f65 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:46 -0600 Subject: [PATCH 200/508] Java autogenerated code to be more compatible with gcs code --- .../templates/uavobjecttemplate.java | 127 +++-- .../java/uavobjectgeneratorjava.cpp | 434 ++++++++---------- .../generators/java/uavobjectgeneratorjava.h | 16 +- 3 files changed, 278 insertions(+), 299 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index fa09f782f..af8f48fce 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -28,61 +28,110 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; -import org.openpilot.uavtalk.UAVObjectField; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) -**/ + **/ public class $(NAME) extends UAVDataObject { + public $(NAME)() throws Exception { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + $(FIELDSINIT) - public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - } + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytesElement(); + } + NUMBYTES = numBytes; + - public void setGeneratedMetaData() { + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } - getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; + } - } - - public int getObjID() { - return $(OBJIDHEX); - } - - public String getObjName() { - return "$(NAME)"; - } + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { +$(INITFIELDS) + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + $(NAME) obj = new $(NAME)(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public $(NAME) GetInstance(UAVObjectManager objMngr, int instID) + { + return ($(NAME))(objMngr.getObject($(NAME).OBJID, instID)); + } - public String getDescription() { - return "$(DESCRIPTION)"; - } -protected: // Constants - static final int OBJID = $(OBJIDHEX); - static final String NAME; - static final String DESCRIPTION; - static final boolean ISSINGLEINST = $(ISSINGLEINST); - static final boolean ISSETTINGS = $(ISSETTINGS); - static final int NUMBYTES = sizeof(DataFields); + protected static final int OBJID = $(OBJIDHEX); + protected static final String NAME = "$(NAME)"; + protected static String DESCRIPTION = "$(DESCRIPTION)"; + protected static final boolean ISSINGLEINST = $(ISSINGLEINST) == 1; + protected static final boolean ISSETTINGS = $(ISSETTINGS) == 1; + protected static int NUMBYTES = 0; -$(GETTERSETTER) } \ No newline at end of file diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 6ac45a07a..ce436e6af 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -24,313 +24,245 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include "uavobjectgeneratorjava.h" using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - QDir javaTemplatePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << + "quint8" << "quint16" << "quint32" << "float" << "quint8"; - javaCodePath = QDir ( outputpath + QString(JAVA_GENERATED_DIR)); + fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" + << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; - javaCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjecttemplate.java") ); - QString javaInitCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjectsinittemplate.java") ); + javaCodePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + javaOutputPath = QDir( outputpath + QString("java") ); + javaOutputPath.mkpath(javaOutputPath.absolutePath()); - if (javaCodeTemplate.isEmpty() || javaInitCodeTemplate.isEmpty()) { - std::cerr << "Problem reading java templates" << endl; + javaCodeTemplate = readFile( javaCodePath.absoluteFilePath("uavobjecttemplate.java") ); + QString javaInitTemplate = readFile( javaCodePath.absoluteFilePath("uavobjectsinittemplate.java") ); + + if (javaCodeTemplate.isEmpty() || javaInitTemplate.isEmpty()) { + std::cerr << "Problem reading java code templates" << endl; return false; } - QString javaObjInit,javaObjGetter; - javaCodePath.mkpath(javaCodePath.absolutePath() + "/uavobjects"); + QString objInc; + QString javaObjInit; for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) { ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - if (!javaObjInit.isNull()) - javaObjInit.append(",\n"); - - javaObjInit.append(" new " + info->name + "()"); - javaObjGetter.append(QString(" public static %1 get%1() { return (%1)uavobjects[%2];}\n").arg( info->name).arg(objidx)); + javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + objInc.append("#include \"" + info->namelc + ".h\"\n"); } - javaInitCodeTemplate.replace("$(OBJINIT)",javaObjInit); - javaInitCodeTemplate.replace("$(OBJGETTER)",javaObjGetter); - - replaceCommonTags(javaInitCodeTemplate); - - // Write the java object inialization files - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/UAVObjects.java", javaInitCodeTemplate ); + // Write the gcs object inialization files + javaInitTemplate.replace( QString("$(OBJINC)"), objInc); + javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); if (!res) { - cerr << "Error: Could not write java init output files" << endl; + cout << "Error: Could not write output files" << endl; return false; } return true; // if we come here everything should be fine } -QString UAVObjectGeneratorJava::getFieldTypeStr(int type,bool as_obj) { - - switch(type) { - case FIELDTYPE_INT8: - return (QString(as_obj?"Byte":"byte")); - case FIELDTYPE_INT16: - case FIELDTYPE_INT32: - case FIELDTYPE_UINT8: - case FIELDTYPE_UINT16: - return (QString(as_obj?"Integer":"int")); - case FIELDTYPE_UINT32: - return (QString(as_obj?"Long":"long")); - case FIELDTYPE_FLOAT32: - return (QString(as_obj?"Float":"float")); - case FIELDTYPE_ENUM: - return (QString(as_obj?"Byte":"byte")); - default: - return QString("error: unknown type"); - } -} - -/** - * - * format a value from FieldInfo with a given index (idx) to a java code snippet - * - */ -QString UAVObjectGeneratorJava::formatJavaValue(FieldInfo* info,int idx) { - switch(info->type) { - case FIELDTYPE_ENUM: - return (info->name.toUpper() + QString("_") + info->defaultValues[idx].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")); - case FIELDTYPE_FLOAT32: - return QString("%1f").arg( info->defaultValues[idx].toFloat() ); - default: - return QString("%1").arg( info->defaultValues[idx].toInt() ); - } -} - -QString UAVObjectGeneratorJava::QStringList2JavaArray(QStringList strl) { - QString csv=QString(); - for (int i = 0; i < strl.length(); i++){ - if (i!=0) - csv.append(QString(",")); - csv.append(QString("\"%1\"").arg(strl[i])); - } - return QString("new String[] { %1 }").arg(csv); -} - -QString UAVObjectGeneratorJava::serializeJavaValue(int type,QString name) -{ - QString res; - switch(type) { - case FIELDTYPE_ENUM: // OK - - case FIELDTYPE_INT8: - res=name; - break; - - case FIELDTYPE_UINT8: - res=QString("(byte)(%1&0xFF)").arg(name); - break; - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF)"); - break; - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF) , (byte)(("+name+">>16)&0xFF) , (byte)(("+name+">>24)&0xFF)"); - break; - - case FIELDTYPE_FLOAT32: - res=QString("(byte)((Float.floatToIntBits("+name+")>>0)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>8)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>16)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>24)&0xFF) "); // OK - break; - - default: - res=QString("unresolved type"); - break; - } - - return res; -} - -/** - * this function is used to build the deserializing code - */ -QString UAVObjectGeneratorJava::deSerializeJavaValue(int type,QString name) -{ - switch(type) { - case FIELDTYPE_ENUM: // OK - case FIELDTYPE_INT8: - return (name.append("=arr[pos++];\n")); - - case FIELDTYPE_UINT8: - return (name.append("=arr[pos++]&0xFF;\n")); /*test */ - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) ;\n")); /* test */ - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ;\n")); /*test */ - - case FIELDTYPE_FLOAT32: - return (name.append("=Float.intBitsToFloat(((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ); ")); // OK - - default: - cout << "Warning: unresolved type " << type << " for " << name.toStdString() << endl; - return(QString("unresolved type")); // will throw an arr when compiling then - } -} /** * Generate the java object files */ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { - if (info == NULL) return false; + if (info == NULL) + return false; // Prepare output strings + QString outInclude = javaIncludeTemplate; QString outCode = javaCodeTemplate; // Replace common tags + replaceCommonTags(outInclude, info); replaceCommonTags(outCode, info); - QString type,fieldsinit,serialize_code,serialize_code_inner,deserialize_code,gettersetter; - - QString fielddesc=QString(" public final UAVObjectFieldDescription[] getFieldDescriptions() { return new UAVObjectFieldDescription[] {"); - QString fieldgetter=QString(" public Object getField(int fieldid,int arr_pos) { switch(fieldid) {\n"); - QString fieldsetter=QString(" public void setField(int fieldid,int arr_pos,Object obj) { switch(fieldid) {\n"); - - for (int n = 0; n < info->fields.length(); ++n) { - FieldInfo* act_field_info=info->fields[n]; - - bool is_array = info->fields[n]->numElements > 1; - type = getFieldTypeStr(act_field_info->type,false); // Determine type - - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) - fieldsinit.append(QString(" public final static byte %1 = %2;\n").arg(act_field_info->name.toUpper() + QString("_") + act_field_info->options[enum_n].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")).arg(enum_n) ); - - fieldsinit.append(QString(" private ") + type); - - if ( is_array ) - fieldsinit.append(QString("[]")); - - fieldsinit.append(QString(" %1").arg(act_field_info->name)); - - if (!info->fields[n]->defaultValues.isEmpty()) { // if we have default vals - fieldsinit.append(QString("=")); - if ( is_array ) { - fieldsinit.append(QString("{")); - for (int val_n = 0; val_n < act_field_info->defaultValues.length(); ++val_n) - fieldsinit.append( ((val_n>0)?QString(","):QString() ) + formatJavaValue(act_field_info,val_n) ); - fieldsinit.append(QString("}")); - } - else - fieldsinit.append(formatJavaValue(act_field_info,0)); - } - else { - if ( is_array ) // when it is an array - fieldsinit.append(QString("= new ") + type + QString("[%1]").arg(info->fields[n]->numElements)); - } - - fieldsinit.append(QString(";\n")); - - if (n!=0) - serialize_code_inner.append(QString(",")); - - if ( is_array ) { - for (int el=0;elfields[n]->numElements;el++) { - if (el!=0) - serialize_code_inner.append(QString(",")); - - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - } - } - else { // no array - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - } - - serialize_code_inner.append(QString("//%1\n" ).arg(info->fields[n]->name)); - + // Replace the $(DATAFIELDS) tag + QString type; + QString fields; + for (int n = 0; n < info->fields.length(); ++n) + { // Determine type - type = getFieldTypeStr(act_field_info->type,false); - - QString typespec=type; - - if ( is_array ) { - typespec.append(QString("[]")); - fieldgetter.append(QString("case %1: return (Object)%2[arr_pos];\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2[arr_pos]=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg( getFieldTypeStr(act_field_info->type,true))); + type = fieldTypeStrCPP[info->fields[n]->type]; + // Append field + if ( info->fields[n]->numElements > 1 ) + { + fields.append( QString(" %1 %2[%3];\n").arg(type).arg(info->fields[n]->name) + .arg(info->fields[n]->numElements) ); } - else { // no array - fieldgetter.append(QString("case %1: return (Object)%2;\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg(getFieldTypeStr(act_field_info->type,true))); + else + { + fields.append( QString(" %1 %2;\n").arg(type).arg(info->fields[n]->name) ); } + } + outInclude.replace(QString("$(DATAFIELDS)"), fields); + // Replace the $(FIELDSINIT) tag + QString finit; + for (int n = 0; n < info->fields.length(); ++n) + { + finit.append("\n"); - if (!act_field_info->units.isEmpty()) // when we have unit info - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); + // Setup element names + QString varElemName = info->fields[n]->name + "ElemNames"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varElemName) ); + QStringList elemNames = info->fields[n]->elementNames; + for (int m = 0; m < elemNames.length(); ++m) + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varElemName) + .arg(elemNames[m]) ); - gettersetter.append(QString(" public void set%1( %2 _%1 ) { %1=_%1; }\n").arg(act_field_info->name).arg(typespec)); - - if (n!=0) - fielddesc.append(QString("\t,")); - - fielddesc.append(QString("new UAVObjectFieldDescription(\"%1\",this.getObjID(),(byte)%2,(byte)%3,\"%4\",%5,%6)\n").arg(act_field_info->name).arg(n).arg(act_field_info->type).arg(act_field_info->units).arg(QStringList2JavaArray( act_field_info->options)).arg(QStringList2JavaArray( act_field_info->elementNames)) ); - - if (!act_field_info->units.isEmpty()) - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); - - gettersetter.append(QString(" public ") + typespec); - - gettersetter.append(QString(" get%1() { return %1; }\n").arg(act_field_info->name)); - - if ( act_field_info->options.length()!=0) { - QString enumOptionsGetter=QString(" public final static String[] get%1EnumOptions() { return new String[] {").arg(act_field_info->name); - - // gettersetter.append(QString(" get%1s() { return %1; }\n").arg(act_field_info->name)); - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) { - if (enum_n!=0) - enumOptionsGetter.append(QString(",")); - enumOptionsGetter.append(QString("\"")+act_field_info->options[enum_n] +QString("\"")); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) { + QString varOptionName = info->fields[n]->name + "EnumOptions"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varOptionName) ); + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) + { + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varOptionName) + .arg(options[m]) ); } - - gettersetter.append(enumOptionsGetter+QString("};}\n")); + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.ENUM, %3, %4) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(varElemName) + .arg(varOptionName) ); } + // For all other types + else { + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.%3, %4, null) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(fieldTypeStrCPPClass[info->fields[n]->type]) + .arg(varElemName) ); + } + } + outCode.replace(QString("$(FIELDSINIT)"), finit); - if ( is_array ) { // when it is an array create getter for the element names - QString elementListGetter=QString(" public final static String[] get%1ElementNames() { return new String[] {").arg(act_field_info->name); + // Replace the $(DATAFIELDINFO) tag + QString name; + QString enums; + for (int n = 0; n < info->fields.length(); ++n) + { + enums.append(QString(" // Field %1 information\n").arg(info->fields[n]->name)); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) + { + enums.append(QString(" /* Enumeration options for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through each option + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) { + QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) + .arg(m) ); + + } + enums.append( QString(" } %1Options;\n") + .arg( info->fields[n]->name ) ); + } + // Generate element names (only if field has more than one element) + if (info->fields[n]->numElements > 1 && !info->fields[n]->defaultElementNames) { + enums.append(QString(" /* Array element names for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through the element names QStringList elemNames = info->fields[n]->elementNames; for (int m = 0; m < elemNames.length(); ++m) { - gettersetter.append(QString(" public ") + type); - gettersetter.append(QString(" get%1%2() { return %1[%3]; }\n").arg(act_field_info->name).arg(elemNames[m]).arg(m)); - if (m!=0) - elementListGetter.append(QString(",")); + QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( elemNames[m].toUpper() ) + .arg(m) ); - elementListGetter.append(QString("\"") + elemNames[m]+QString("\"")); } - gettersetter.append(elementListGetter+QString("};}\n")); + enums.append( QString(" } %1Elem;\n") + .arg( info->fields[n]->name ) ); + } + // Generate array information + if (info->fields[n]->numElements > 1) { + enums.append(QString(" /* Number of elements for field %1 */\n").arg(info->fields[n]->name)); + enums.append( QString(" static const quint32 %1_NUMELEM = %2;\n") + .arg( info->fields[n]->name.toUpper() ) + .arg( info->fields[n]->numElements ) ); + } + } + outInclude.replace(QString("$(DATAFIELDINFO)"), enums); + + // Replace the $(INITFIELDS) tag + QString initfields; + for (int n = 0; n < info->fields.length(); ++n) + { + if (!info->fields[n]->defaultValues.isEmpty() ) + { + // For non-array fields + if ( info->fields[n]->numElements == 1) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toFloat() ) ); + } + else + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toInt() ) ); + } + } + else + { + // Initialize all fields in the array + for (int idx = 0; idx < info->fields[n]->numElements; ++idx) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toFloat() ) ); + } + else { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toInt() ) ); + } + } + } } } - serialize_code.append(QString(" public byte[] serialize() { return new byte[]{%1 } ;}; \n ").arg(serialize_code_inner)); + outCode.replace(QString("$(INITFIELDS)"), initfields); - serialize_code.append(QString(" public void deserialize(byte[] arr,int offset) {\nsuper.deserialize(arr,offset);\n int pos=offset;\n%1 };\n").arg(deserialize_code)); - - outCode.replace(QString("$(FIELDSINIT)"), fieldsinit); - - fielddesc.append(QString("};}")); - fieldgetter.append(QString("};\n return null;\n}\n")); - fieldsetter.append(QString("};\n}\n")); - outCode.replace(QString("$(GETTERSETTER)"), gettersetter + serialize_code+ fielddesc + fieldgetter + fieldsetter); - - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/uavobjects/" + info->name + ".java", outCode ); + // Write the java code + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); if (!res) { - cerr << "Error: Could not write java init output file " << info->name.toStdString()<< endl; + cout << "Error: Could not write gcs output files" << endl; return false; - } + } return true; } diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h index 21fc4dc75..8d07484f6 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h @@ -28,7 +28,7 @@ #define UAVOBJECTGENERATORJAVA_H #define JAVA_TEMPLATE_DIR "ground/openpilotgcs/src/libs/juavobjects/templates/" -#define JAVA_GENERATED_DIR "java/src/org/openpilot/uavtalk" +#define JAVA_CODE_DIR "java/src/org/openpilot/uavtalk" #include "../generator_common.h" @@ -38,14 +38,12 @@ public: bool generate(UAVObjectParser* gen,QString templatepath,QString outputpath); private: - QString javaCodeTemplate; - QDir javaCodePath; bool process_object(ObjectInfo* info); - QString formatJavaValue(FieldInfo* info,int idx); - QString QStringList2JavaArray(QStringList strl); - QString serializeJavaValue(int type,QString name); - QString deSerializeJavaValue(int type,QString name); - QString getFieldTypeStr(int type,bool as_obj); -}; + + QString javaCodeTemplate, javaIncludeTemplate; + QStringList fieldTypeStrCPP,fieldTypeStrCPPClass; + QDir javaCodePath; + QDir javaOutputPath; + }; #endif From f41980c27631dfd8cbfa3d3b9c759195a10ad1f7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:56:56 -0600 Subject: [PATCH 201/508] Remove some debugging lines, also use Number interface instead of explicit Byte, Integer, Short etc in setValue/getValue --- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 118 +++++++++++------- 2 files changed, 77 insertions(+), 46 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 926440805..fe478cf2e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -114,7 +114,7 @@ public abstract class UAVObject { for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } -// unpack(data); + unpack(data); } /** @@ -291,13 +291,12 @@ public abstract class UAVObject { public int unpack(ByteBuffer dataIn) throws Exception { if( dataIn == null ) return 0; - System.out.println( dataIn.toString() ); + // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); while (li.hasNext()) { UAVObjectField field = li.next(); - System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index b37c992fb..a9006e02f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -99,31 +99,43 @@ public class UAVObjectField { switch (type) { case INT8: - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case INT16: - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case INT32: - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case UINT8: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case UINT16: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case UINT32: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case FLOAT32: for (int index = 0; index < numElements; ++index) @@ -142,64 +154,93 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) { case INT8: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case INT16: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case INT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case UINT8: - // TODO: Deal with unsigned + // TOOD: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case UINT16: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case UINT32: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case FLOAT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Float) dataIn.getFloat(), index); + Float val = dataIn.getFloat(); + l.set(index, val); } break; + } case ENUM: + { List l = (List) data; for (int index = 0 ; index < numElements; ++index) { l.set(index, dataIn.get(index)); } break; + } case STRING: - throw new Exception("Strings not handled"); + // TODO: implement strings + //throw new Exception("Strings not handled"); } // Done return getNumBytes(); } - Object getValue() throws Exception { return getValue(0); }; - Object getValue(int index) throws Exception { + Object getValue() { return getValue(0); }; + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) @@ -234,14 +275,14 @@ public class UAVObjectField { List l = (List) data; Byte val = l.get(index); - if(val >= options.size() || val < 0) - throw new Exception("Invalid value for" + name); + //if(val >= options.size() || val < 0) + // throw new Exception("Invalid value for" + name); return options.get(val); } case STRING: { - throw new Exception("Shit I should do this"); + //throw new Exception("Shit I should do this"); } } // If this point is reached then we got an invalid type @@ -252,12 +293,9 @@ public class UAVObjectField { public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ) + if ( index >= numElements ); //throw new Exception("Index out of bounds"); - System.out.println(data.toString()); - System.out.println(this.data.toString()); - // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits @@ -266,23 +304,19 @@ public class UAVObjectField { switch (type) { case INT8: - data = new Integer((Byte) data); case INT16: - data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index,(Integer) data); + l.set(index,((Number) data).intValue()); break; } case UINT8: - data = new Integer((Byte) data); case UINT16: - data = new Integer((Short) data); case UINT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,((Number) data).intValue()); break; } case FLOAT32: @@ -386,7 +420,7 @@ public class UAVObjectField { sout += name + ": [ "; for (int n = 0; n < numElements; ++n) { - sout += String.valueOf(n) + " "; + sout += String.valueOf(n) + "(" + getValue(n) + ") "; } sout += "] " + units + "\n"; @@ -442,9 +476,8 @@ public class UAVObjectField { this.data = null; this.obj = null; this.elementNames = elementNames; - // Set field size - System.out.println("Initializing: type " + type + this.numElements); + // Set field size switch (type) { case INT8: @@ -487,7 +520,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - System.out.println("Initialized: " + this.data.toString()); } From 5aa8eb522a96b93c2823731d1c7c92a22e1dd4eb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 02:26:09 -0600 Subject: [PATCH 202/508] Make object store with the minimal amount of space and deal with unsigned values --- .../src/org/openpilot/uavtalk/UAVObject.java | 4 +- .../org/openpilot/uavtalk/UAVObjectField.java | 203 +++++++++++++----- .../java/uavobjectgeneratorjava.cpp | 4 +- 3 files changed, 148 insertions(+), 63 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fe478cf2e..bf2c87d7e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -462,9 +462,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; - // getName(), getObjID(), getInstID(), getNumBytes(), - // isSingleInstance()); + return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a9006e02f..78ebd7b52 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -27,8 +27,7 @@ public class UAVObjectField { public void initialize(UAVObject obj){ this.obj = obj; - clear(); - + //clear(); } public UAVObject getObject() { @@ -161,19 +160,19 @@ public class UAVObjectField { { case INT8: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + Long val = bound(dataIn.get()); + l.set(index, val.byteValue()); } break; } case INT16: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + Long val = bound(dataIn.getShort()); + l.set(index, val.shortValue()); } break; } @@ -181,18 +180,18 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); + Long val = bound(dataIn.getInt()); l.set(index, val.intValue()); } break; } case UINT8: - // TOOD: Deal with unsigned { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); } break; } @@ -200,17 +199,19 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.getShort(); // this sign extends it + int unsignedval = signedval & 0xffff; // drop sign extension + l.set(index, unsignedval); } break; } case UINT32: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); - l.set(index, val.intValue()); + long signedval = (long) dataIn.getInt(); // this sign extends it + long unsignedval = signedval & 0xffffffffL; // drop sign extension + l.set(index, unsignedval); } break; } @@ -240,36 +241,31 @@ public class UAVObjectField { } Object getValue() { return getValue(0); }; - Object getValue(int index) { + @SuppressWarnings("unchecked") + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) { return null; } - + switch (type) { case INT8: + return ((List) data).get(index).intValue(); case INT16: + return ((List) data).get(index).intValue(); case INT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index).intValue(); case UINT8: + return ((List) data).get(index).intValue(); case UINT16: + return ((List) data).get(index).intValue(); case UINT32: - { - // TODO: Correctly deal with unsigned values - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case FLOAT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case ENUM: { List l = (List) data; @@ -290,10 +286,11 @@ public class UAVObjectField { } public void setValue(Object data) { setValue(data,0); } - public void setValue(Object data, int index) { + @SuppressWarnings("unchecked") + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ); + //if ( index >= numElements ); //throw new Exception("Index out of bounds"); // Get metadata @@ -304,25 +301,45 @@ public class UAVObjectField { switch (type) { case INT8: + { + List l = (List) this.data; + l.set(index, bound(data).byteValue()); + break; + } case INT16: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case INT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); break; } case UINT8: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case UINT16: - case UINT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); + break; + } + case UINT32: + { + List l = (List) this.data; + l.set(index, bound(data)); break; } case FLOAT32: { List l = (List) this.data; - l.set(index, (Float) data); + l.set(index, ((Number) data).floatValue()); break; } case ENUM: @@ -431,37 +448,46 @@ public class UAVObjectField { } - public void clear() { + @SuppressWarnings("unchecked") + public void clear() { switch (type) { case INT8: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; case INT16: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case INT32: - case UINT8: - case UINT16: - case UINT32: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { ((ArrayList) data).add(0); } break; - case FLOAT32: - ((ArrayList) data).clear(); + case UINT8: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((float) 0); + ((ArrayList) data).add((short) 0); } break; - case ENUM: - ((ArrayList) data).clear(); + case UINT16: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((byte)0); + ((ArrayList) data).add(0); } break; - case STRING: - // TODO: Add string + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((long) 0); + } break; - default: - numBytesPerElement = 0; } } @@ -481,11 +507,11 @@ public class UAVObjectField { switch (type) { case INT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: @@ -493,7 +519,7 @@ public class UAVObjectField { numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: @@ -501,11 +527,11 @@ public class UAVObjectField { numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: @@ -520,8 +546,69 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); + + System.out.println(this); } + /** + * For numerical types bounds the data appropriately + * @param val Can be any object, for numerical tries to cast to Number + * @return long value with the right range (for float rounds) + * @note This is mostly needed because java has no unsigned integer + */ + protected Long bound (Object val) { + + switch(type) { + case ENUM: + case STRING: + return 0L; + case FLOAT32: + return ((Number) val).longValue(); + } + + long num = ((Number) val).longValue(); + + switch(type) { + case INT8: + if(num < Byte.MIN_VALUE) + return (long) Byte.MAX_VALUE; + if(num > Byte.MAX_VALUE) + return (long) Byte.MAX_VALUE; + return num; + case INT16: + if(num < Short.MIN_VALUE) + return (long) Short.MIN_VALUE; + if(num > Short.MAX_VALUE) + return (long) Short.MAX_VALUE; + return num; + case INT32: + if(num < Integer.MIN_VALUE) + return (long) Integer.MIN_VALUE; + if(num > Integer.MAX_VALUE) + return (long) Integer.MAX_VALUE; + return num; + case UINT8: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; + case UINT16: + if(num < 0) + return (long) 0; + if(num > 65535) + return (long) 65535; + return num; + case UINT32: + if(num < 0) + return (long) 0; + if(num > 4294967295L) + return 4294967295L; + return num; + } + + return num; + } private String name; private String units; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index ce436e6af..7319b7767 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -29,8 +29,8 @@ using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << - "quint8" << "quint16" << "quint32" << "float" << "quint8"; + fieldTypeStrCPP << "Byte" << "Short" << "Int" << + "Short" << "Int" << "Long" << "Float" << "Byte"; fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; From 5220ddc2014b917372b4657bd519334b4c4c5c04 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:10:48 -0600 Subject: [PATCH 203/508] Added unit tests --- .../org/openpilot/uavtalk/FieldTest.java | 121 ++++++++++++++++++ .../org/openpilot/uavtalk/SettingsTest.java | 34 +++++ 2 files changed, 155 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/FieldTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java new file mode 100644 index 000000000..2d161fc25 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java @@ -0,0 +1,121 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + +import org.junit.BeforeClass; +import org.junit.Test; + +import org.openpilot.uavtalk.UAVObjectField; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.uavobjects.*; + +public class FieldTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testPackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + + try { + field.pack(bbuf); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Buffer size incorrect"); + } + + // Expect data to come out as little endian + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + for(int i = 0; i < expected.length && i < bbuf.array().length; i++) { + System.out.println("Expected: " + expected[i] + " (" + i + ")"); + System.out.println("Received: " + bbuf.array()[i] + " (" + i + ")"); + assertEquals(bbuf.array()[i],expected[i]); + } + } + + @Test + public void testUnpackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + obj = new ActuatorCommand(); + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + bbuf.put(expected); + bbuf.position(0); + field.unpack(bbuf); + + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } + + @Test + public void testEnumSetGetValue() { + List options = new ArrayList(); + options.add("Opt1"); + options.add("Opt2"); + options.add("Opt3"); + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.ENUM, 3, options); + field.initialize(obj); + field.setValue("Opt1",0); + field.setValue("Opt2",1); + field.setValue("Opt3",2); + assertEquals(field.getValue(0), "Opt1"); + assertEquals(field.getValue(1), "Opt2"); + assertEquals(field.getValue(2), "Opt3"); + } + + @Test + public void testUint16SetGetValue() { + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java new file mode 100644 index 000000000..5a805ae88 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java @@ -0,0 +1,34 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; + +public class SettingsTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetDefaultMetadata() { + fail("Not yet implemented"); + } + + @Test + public void testSetDefaultFieldValues() { + fail("Not yet implemented"); + } + + @Test + public void testIsSettings() { + fail("Not yet implemented"); + } + + @Test + public void testGetField() { + fail("Not yet implemented"); + } + +} From b98bdb9be0fd1bebea973871d0538cd33fb02c3e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:11:07 -0600 Subject: [PATCH 204/508] More updates to the java objects. Also checking in the auto generated code for now to make things easier. --- .../uavtalk/uavobjects/AHRSCalibration.java | 243 ++++++++++ .../uavtalk/uavobjects/AHRSSettings.java | 178 +++++++ .../uavtalk/uavobjects/ActuatorCommand.java | 158 ++++++ .../uavtalk/uavobjects/ActuatorDesired.java | 159 ++++++ .../uavtalk/uavobjects/ActuatorSettings.java | 455 ++++++++++++++++++ .../uavtalk/uavobjects/AhrsStatus.java | 201 ++++++++ .../uavtalk/uavobjects/AttitudeActual.java | 163 +++++++ .../uavtalk/uavobjects/AttitudeRaw.java | 158 ++++++ .../uavtalk/uavobjects/AttitudeSettings.java | 159 ++++++ .../uavtalk/uavobjects/BaroAltitude.java | 147 ++++++ .../uavtalk/uavobjects/BatterySettings.java | 163 +++++++ .../uavtalk/uavobjects/FirmwareIAPObj.java | 258 ++++++++++ .../uavobjects/FlightBatteryState.java | 165 +++++++ .../uavtalk/uavobjects/FlightPlanControl.java | 144 ++++++ .../uavobjects/FlightPlanSettings.java | 140 ++++++ .../uavtalk/uavobjects/FlightPlanStatus.java | 187 +++++++ .../uavobjects/FlightTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GPSPosition.java | 184 +++++++ .../uavtalk/uavobjects/GPSSatellites.java | 215 +++++++++ .../openpilot/uavtalk/uavobjects/GPSTime.java | 159 ++++++ .../uavtalk/uavobjects/GuidanceSettings.java | 197 ++++++++ .../uavtalk/uavobjects/HomeLocation.java | 197 ++++++++ .../uavtalk/uavobjects/I2CStats.java | 238 +++++++++ .../uavobjects/ManualControlCommand.java | 199 ++++++++ .../uavobjects/ManualControlSettings.java | 395 +++++++++++++++ .../uavtalk/uavobjects/MixerSettings.java | 357 ++++++++++++++ .../uavtalk/uavobjects/MixerStatus.java | 167 +++++++ .../uavtalk/uavobjects/NedAccel.java | 147 ++++++ .../uavtalk/uavobjects/ObjectPersistence.java | 160 ++++++ .../uavtalk/uavobjects/PositionActual.java | 147 ++++++ .../uavtalk/uavobjects/PositionDesired.java | 147 ++++++ .../uavtalk/uavobjects/RateDesired.java | 147 ++++++ .../uavtalk/uavobjects/SonarAltitude.java | 139 ++++++ .../uavobjects/StabilizationDesired.java | 161 +++++++ .../uavobjects/StabilizationSettings.java | 222 +++++++++ .../uavtalk/uavobjects/SystemAlarms.java | 176 +++++++ .../uavtalk/uavobjects/SystemSettings.java | 157 ++++++ .../uavtalk/uavobjects/SystemStats.java | 151 ++++++ .../uavtalk/uavobjects/TaskInfo.java | 170 +++++++ .../uavtalk/uavobjects/TelemetrySettings.java | 148 ++++++ .../uavobjects/UAVObjectsInitialize.java | 87 ++++ .../uavtalk/uavobjects/VelocityActual.java | 147 ++++++ .../uavtalk/uavobjects/VelocityDesired.java | 147 ++++++ .../uavtalk/uavobjects/WatchdogStatus.java | 143 ++++++ 45 files changed, 8310 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java new file mode 100644 index 000000000..a3096ad39 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -0,0 +1,243 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the calibration settings for the @ref AHRSCommsModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the calibration settings for the @ref AHRSCommsModule + +generated from ahrscalibration.xml + **/ +public class AHRSCalibration extends UAVDataObject { + + public AHRSCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcompfactorElemNames = new ArrayList(); + gyro_tempcompfactorElemNames.add("X"); + gyro_tempcompfactorElemNames.add("Y"); + gyro_tempcompfactorElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List vel_varElemNames = new ArrayList(); + vel_varElemNames.add("0"); + fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); + + List pos_varElemNames = new ArrayList(); + pos_varElemNames.add("0"); + fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("measure_var").setValue(0); + getField("accel_bias").setValue(-73.5,0); + getField("accel_bias").setValue(-73.5,1); + getField("accel_bias").setValue(73.5,2); + getField("accel_scale").setValue(0.0359,0); + getField("accel_scale").setValue(0.0359,1); + getField("accel_scale").setValue(-0.0359,2); + getField("accel_var").setValue(0.0005,0); + getField("accel_var").setValue(0.0005,1); + getField("accel_var").setValue(0.0005,2); + getField("gyro_bias").setValue(23,0); + getField("gyro_bias").setValue(-23,1); + getField("gyro_bias").setValue(23,2); + getField("gyro_scale").setValue(-0.017,0); + getField("gyro_scale").setValue(0.017,1); + getField("gyro_scale").setValue(-0.017,2); + getField("gyro_var").setValue(0.0001,0); + getField("gyro_var").setValue(0.0001,1); + getField("gyro_var").setValue(0.0001,2); + getField("gyro_tempcompfactor").setValue(0,0); + getField("gyro_tempcompfactor").setValue(0,1); + getField("gyro_tempcompfactor").setValue(0,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(-2,0); + getField("mag_scale").setValue(-2,1); + getField("mag_scale").setValue(-2,2); + getField("mag_var").setValue(50,0); + getField("mag_var").setValue(50,1); + getField("mag_var").setValue(50,2); + getField("vel_var").setValue(0.4); + getField("pos_var").setValue(0.4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSCalibration obj = new AHRSCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x30101BB2; + protected static final String NAME = "AHRSCalibration"; + protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java new file mode 100644 index 000000000..a38915c28 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + +generated from ahrssettings.xml + **/ +public class AHRSSettings extends UAVDataObject { + + public AHRSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlgorithmElemNames = new ArrayList(); + AlgorithmElemNames.add("0"); + List AlgorithmEnumOptions = new ArrayList(); + AlgorithmEnumOptions.add("SIMPLE"); + AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); + AlgorithmEnumOptions.add("INSGPS_INDOOR"); + AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); + fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); + + List DownsamplingElemNames = new ArrayList(); + DownsamplingElemNames.add("0"); + fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("TRUE"); + BiasCorrectedRawEnumOptions.add("FALSE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Algorithm").setValue(1); + getField("Downsampling").setValue(20); + getField("UpdatePeriod").setValue(1); + getField("BiasCorrectedRaw").setValue(0); + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSSettings obj = new AHRSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDEFC5548; + protected static final String NAME = "AHRSSettings"; + protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java new file mode 100644 index 000000000..a5d6230ac --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + +generated from actuatorcommand.xml + **/ +public class ActuatorCommand extends UAVDataObject { + + public ActuatorCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + + List MaxUpdateTimeElemNames = new ArrayList(); + MaxUpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + + List NumFailedUpdatesElemNames = new ArrayList(); + NumFailedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorCommand obj = new ActuatorCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorCommand)(objMngr.getObject(ActuatorCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE8E077D8; + protected static final String NAME = "ActuatorCommand"; + protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java new file mode 100644 index 000000000..b81ca29da --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + +generated from actuatordesired.xml + **/ +public class ActuatorDesired extends UAVDataObject { + + public ActuatorDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.FLOAT32, UpdateTimeElemNames, null) ); + + List NumLongUpdatesElemNames = new ArrayList(); + NumLongUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumLongUpdates", "ms", UAVObjectField.FieldType.FLOAT32, NumLongUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorDesired obj = new ActuatorDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorDesired)(objMngr.getObject(ActuatorDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD4516782; + protected static final String NAME = "ActuatorDesired"; + protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java new file mode 100644 index 000000000..ebbfaeb17 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -0,0 +1,455 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from actuatorsettings.xml + **/ +public class ActuatorSettings extends UAVDataObject { + + public ActuatorSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYawElemNames = new ArrayList(); + FixedWingYawElemNames.add("0"); + List FixedWingYawEnumOptions = new ArrayList(); + FixedWingYawEnumOptions.add("Channel1"); + FixedWingYawEnumOptions.add("Channel2"); + FixedWingYawEnumOptions.add("Channel3"); + FixedWingYawEnumOptions.add("Channel4"); + FixedWingYawEnumOptions.add("Channel5"); + FixedWingYawEnumOptions.add("Channel6"); + FixedWingYawEnumOptions.add("Channel7"); + FixedWingYawEnumOptions.add("Channel8"); + FixedWingYawEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + + List ChannelUpdateFreqElemNames = new ArrayList(); + ChannelUpdateFreqElemNames.add("0"); + ChannelUpdateFreqElemNames.add("1"); + ChannelUpdateFreqElemNames.add("2"); + ChannelUpdateFreqElemNames.add("3"); + fields.add( new UAVObjectField("ChannelUpdateFreq", "Hz", UAVObjectField.FieldType.UINT16, ChannelUpdateFreqElemNames, null) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ChannelTypeElemNames = new ArrayList(); + ChannelTypeElemNames.add("0"); + ChannelTypeElemNames.add("1"); + ChannelTypeElemNames.add("2"); + ChannelTypeElemNames.add("3"); + ChannelTypeElemNames.add("4"); + ChannelTypeElemNames.add("5"); + ChannelTypeElemNames.add("6"); + ChannelTypeElemNames.add("7"); + List ChannelTypeEnumOptions = new ArrayList(); + ChannelTypeEnumOptions.add("PWM"); + ChannelTypeEnumOptions.add("MK"); + ChannelTypeEnumOptions.add("ASTEC4"); + fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); + + List ChannelAddrElemNames = new ArrayList(); + ChannelAddrElemNames.add("0"); + ChannelAddrElemNames.add("1"); + ChannelAddrElemNames.add("2"); + ChannelAddrElemNames.add("3"); + ChannelAddrElemNames.add("4"); + ChannelAddrElemNames.add("5"); + ChannelAddrElemNames.add("6"); + ChannelAddrElemNames.add("7"); + fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FixedWingRoll1").setValue(8); + getField("FixedWingRoll2").setValue(8); + getField("FixedWingPitch1").setValue(8); + getField("FixedWingPitch2").setValue(8); + getField("FixedWingYaw").setValue(8); + getField("FixedWingThrottle").setValue(8); + getField("VTOLMotorN").setValue(8); + getField("VTOLMotorNE").setValue(8); + getField("VTOLMotorE").setValue(8); + getField("VTOLMotorSE").setValue(8); + getField("VTOLMotorS").setValue(8); + getField("VTOLMotorSW").setValue(8); + getField("VTOLMotorW").setValue(8); + getField("VTOLMotorNW").setValue(8); + getField("ChannelUpdateFreq").setValue(50,0); + getField("ChannelUpdateFreq").setValue(50,1); + getField("ChannelUpdateFreq").setValue(50,2); + getField("ChannelUpdateFreq").setValue(50,3); + getField("ChannelMax").setValue(1000,0); + getField("ChannelMax").setValue(1000,1); + getField("ChannelMax").setValue(1000,2); + getField("ChannelMax").setValue(1000,3); + getField("ChannelMax").setValue(1000,4); + getField("ChannelMax").setValue(1000,5); + getField("ChannelMax").setValue(1000,6); + getField("ChannelMax").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,0); + getField("ChannelNeutral").setValue(1000,1); + getField("ChannelNeutral").setValue(1000,2); + getField("ChannelNeutral").setValue(1000,3); + getField("ChannelNeutral").setValue(1000,4); + getField("ChannelNeutral").setValue(1000,5); + getField("ChannelNeutral").setValue(1000,6); + getField("ChannelNeutral").setValue(1000,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ChannelType").setValue(0,0); + getField("ChannelType").setValue(0,1); + getField("ChannelType").setValue(0,2); + getField("ChannelType").setValue(0,3); + getField("ChannelType").setValue(0,4); + getField("ChannelType").setValue(0,5); + getField("ChannelType").setValue(0,6); + getField("ChannelType").setValue(0,7); + getField("ChannelAddr").setValue(0,0); + getField("ChannelAddr").setValue(1,1); + getField("ChannelAddr").setValue(2,2); + getField("ChannelAddr").setValue(3,3); + getField("ChannelAddr").setValue(4,4); + getField("ChannelAddr").setValue(5,5); + getField("ChannelAddr").setValue(6,6); + getField("ChannelAddr").setValue(7,7); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorSettings obj = new ActuatorSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorSettings)(objMngr.getObject(ActuatorSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1BF864C2; + protected static final String NAME = "ActuatorSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java new file mode 100644 index 000000000..3ee8304ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -0,0 +1,201 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the @ref AHRSCommsModule, including communication errors + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the @ref AHRSCommsModule, including communication errors + +generated from ahrsstatus.xml + **/ +public class AhrsStatus extends UAVDataObject { + + public AhrsStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SerialNumberElemNames = new ArrayList(); + SerialNumberElemNames.add("0"); + SerialNumberElemNames.add("1"); + SerialNumberElemNames.add("2"); + SerialNumberElemNames.add("3"); + SerialNumberElemNames.add("4"); + SerialNumberElemNames.add("5"); + SerialNumberElemNames.add("6"); + SerialNumberElemNames.add("7"); + fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + + List IdleTimePerCyleElemNames = new ArrayList(); + IdleTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); + + List RunningTimePerCyleElemNames = new ArrayList(); + RunningTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); + + List LinkRunningElemNames = new ArrayList(); + LinkRunningElemNames.add("0"); + List LinkRunningEnumOptions = new ArrayList(); + LinkRunningEnumOptions.add("FALSE"); + LinkRunningEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); + + List AhrsKickstartsElemNames = new ArrayList(); + AhrsKickstartsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); + + List AhrsCrcErrorsElemNames = new ArrayList(); + AhrsCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); + + List AhrsRetriesElemNames = new ArrayList(); + AhrsRetriesElemNames.add("0"); + fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); + + List AhrsInvalidPacketsElemNames = new ArrayList(); + AhrsInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); + + List OpCrcErrorsElemNames = new ArrayList(); + OpCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); + + List OpRetriesElemNames = new ArrayList(); + OpRetriesElemNames.add("0"); + fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); + + List OpInvalidPacketsElemNames = new ArrayList(); + OpInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AhrsStatus obj = new AhrsStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37A5F7A2; + protected static final String NAME = "AhrsStatus"; + protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java new file mode 100644 index 000000000..714c18571 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The updated Attitude estimation from @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The updated Attitude estimation from @ref AHRSCommsModule. + +generated from attitudeactual.xml + **/ +public class AttitudeActual extends UAVDataObject { + + public AttitudeActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 500; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeActual obj = new AttitudeActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeActual)(objMngr.getObject(AttitudeActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFC5B8CF4; + protected static final String NAME = "AttitudeActual"; + protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java new file mode 100644 index 000000000..d28302b6a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + +generated from attituderaw.xml + **/ +public class AttitudeRaw extends UAVDataObject { + + public AttitudeRaw() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrosElemNames = new ArrayList(); + gyrosElemNames.add("X"); + gyrosElemNames.add("Y"); + gyrosElemNames.add("Z"); + fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + + List accelsElemNames = new ArrayList(); + accelsElemNames.add("X"); + accelsElemNames.add("Y"); + accelsElemNames.add("Z"); + fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeRaw obj = new AttitudeRaw(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37747DE6; + protected static final String NAME = "AttitudeRaw"; + protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java new file mode 100644 index 000000000..482fc12ce --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref Attitude module used on CopterControl + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref Attitude module used on CopterControl + +generated from attitudesettings.xml + **/ +public class AttitudeSettings extends UAVDataObject { + + public AttitudeSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroGainElemNames = new ArrayList(); + GyroGainElemNames.add("0"); + fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); + + List AccelKpElemNames = new ArrayList(); + AccelKpElemNames.add("0"); + fields.add( new UAVObjectField("AccelKp", "channel", UAVObjectField.FieldType.FLOAT32, AccelKpElemNames, null) ); + + List AccelKiElemNames = new ArrayList(); + AccelKiElemNames.add("0"); + fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AccelBias").setValue(0,0); + getField("AccelBias").setValue(0,1); + getField("AccelBias").setValue(0,2); + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.01); + getField("AccelKi").setValue(0.0001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSettings obj = new AttitudeSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSettings)(objMngr.getObject(AttitudeSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x327BF29A; + protected static final String NAME = "AttitudeSettings"; + protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java new file mode 100644 index 000000000..a2c2c7e3d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the barometric sensor with pressure, temperature and altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the barometric sensor with pressure, temperature and altitude estimate. + +generated from baroaltitude.xml + **/ +public class BaroAltitude extends UAVDataObject { + + public BaroAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List TemperatureElemNames = new ArrayList(); + TemperatureElemNames.add("0"); + fields.add( new UAVObjectField("Temperature", "C", UAVObjectField.FieldType.FLOAT32, TemperatureElemNames, null) ); + + List PressureElemNames = new ArrayList(); + PressureElemNames.add("0"); + fields.add( new UAVObjectField("Pressure", "kPa", UAVObjectField.FieldType.FLOAT32, PressureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAltitude obj = new BaroAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAltitude)(objMngr.getObject(BaroAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xED4424F6; + protected static final String NAME = "BaroAltitude"; + protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java new file mode 100644 index 000000000..19e477b62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery configuration information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery configuration information. + +generated from batterysettings.xml + **/ +public class BatterySettings extends UAVDataObject { + + public BatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BatteryVoltageElemNames = new ArrayList(); + BatteryVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + + List BatteryCapacityElemNames = new ArrayList(); + BatteryCapacityElemNames.add("0"); + fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); + + List BatteryTypeElemNames = new ArrayList(); + BatteryTypeElemNames.add("0"); + List BatteryTypeEnumOptions = new ArrayList(); + BatteryTypeEnumOptions.add("LiPo"); + BatteryTypeEnumOptions.add("A123"); + BatteryTypeEnumOptions.add("LiCo"); + BatteryTypeEnumOptions.add("LiFeSO4"); + BatteryTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); + + List CalibrationsElemNames = new ArrayList(); + CalibrationsElemNames.add("Voltage"); + CalibrationsElemNames.add("Current"); + fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("BatteryVoltage").setValue(11.1); + getField("BatteryCapacity").setValue(2200); + getField("BatteryType").setValue(0); + getField("Calibrations").setValue(1,0); + getField("Calibrations").setValue(1,1); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BatterySettings obj = new BatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA5FF1D9A; + protected static final String NAME = "BatterySettings"; + protected static String DESCRIPTION = "Battery configuration information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java new file mode 100644 index 000000000..493d6cd64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -0,0 +1,258 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Firmware IAP + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Firmware IAP + +generated from firmwareiapobj.xml + **/ +public class FirmwareIAPObj extends UAVDataObject { + + public FirmwareIAPObj() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + DescriptionElemNames.add("40"); + DescriptionElemNames.add("41"); + DescriptionElemNames.add("42"); + DescriptionElemNames.add("43"); + DescriptionElemNames.add("44"); + DescriptionElemNames.add("45"); + DescriptionElemNames.add("46"); + DescriptionElemNames.add("47"); + DescriptionElemNames.add("48"); + DescriptionElemNames.add("49"); + DescriptionElemNames.add("50"); + DescriptionElemNames.add("51"); + DescriptionElemNames.add("52"); + DescriptionElemNames.add("53"); + DescriptionElemNames.add("54"); + DescriptionElemNames.add("55"); + DescriptionElemNames.add("56"); + DescriptionElemNames.add("57"); + DescriptionElemNames.add("58"); + DescriptionElemNames.add("59"); + DescriptionElemNames.add("60"); + DescriptionElemNames.add("61"); + DescriptionElemNames.add("62"); + DescriptionElemNames.add("63"); + DescriptionElemNames.add("64"); + DescriptionElemNames.add("65"); + DescriptionElemNames.add("66"); + DescriptionElemNames.add("67"); + DescriptionElemNames.add("68"); + DescriptionElemNames.add("69"); + DescriptionElemNames.add("70"); + DescriptionElemNames.add("71"); + DescriptionElemNames.add("72"); + DescriptionElemNames.add("73"); + DescriptionElemNames.add("74"); + DescriptionElemNames.add("75"); + DescriptionElemNames.add("76"); + DescriptionElemNames.add("77"); + DescriptionElemNames.add("78"); + DescriptionElemNames.add("79"); + DescriptionElemNames.add("80"); + DescriptionElemNames.add("81"); + DescriptionElemNames.add("82"); + DescriptionElemNames.add("83"); + DescriptionElemNames.add("84"); + DescriptionElemNames.add("85"); + DescriptionElemNames.add("86"); + DescriptionElemNames.add("87"); + DescriptionElemNames.add("88"); + DescriptionElemNames.add("89"); + DescriptionElemNames.add("90"); + DescriptionElemNames.add("91"); + DescriptionElemNames.add("92"); + DescriptionElemNames.add("93"); + DescriptionElemNames.add("94"); + DescriptionElemNames.add("95"); + DescriptionElemNames.add("96"); + DescriptionElemNames.add("97"); + DescriptionElemNames.add("98"); + DescriptionElemNames.add("99"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List ArmResetElemNames = new ArrayList(); + ArmResetElemNames.add("0"); + fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); + + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FirmwareIAPObj obj = new FirmwareIAPObj(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FirmwareIAPObj GetInstance(UAVObjectManager objMngr, int instID) + { + return (FirmwareIAPObj)(objMngr.getObject(FirmwareIAPObj.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1A8ECC2; + protected static final String NAME = "FirmwareIAPObj"; + protected static String DESCRIPTION = "Firmware IAP"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java new file mode 100644 index 000000000..d9fba1de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery status information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery status information. + +generated from flightbatterystate.xml + **/ +public class FlightBatteryState extends UAVDataObject { + + public FlightBatteryState() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List VoltageElemNames = new ArrayList(); + VoltageElemNames.add("0"); + fields.add( new UAVObjectField("Voltage", "V", UAVObjectField.FieldType.FLOAT32, VoltageElemNames, null) ); + + List CurrentElemNames = new ArrayList(); + CurrentElemNames.add("0"); + fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + + List PeakCurrentElemNames = new ArrayList(); + PeakCurrentElemNames.add("0"); + fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); + + List AvgCurrentElemNames = new ArrayList(); + AvgCurrentElemNames.add("0"); + fields.add( new UAVObjectField("AvgCurrent", "A", UAVObjectField.FieldType.FLOAT32, AvgCurrentElemNames, null) ); + + List ConsumedEnergyElemNames = new ArrayList(); + ConsumedEnergyElemNames.add("0"); + fields.add( new UAVObjectField("ConsumedEnergy", "mAh", UAVObjectField.FieldType.FLOAT32, ConsumedEnergyElemNames, null) ); + + List EstimatedFlightTimeElemNames = new ArrayList(); + EstimatedFlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("EstimatedFlightTime", "sec", UAVObjectField.FieldType.FLOAT32, EstimatedFlightTimeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Voltage").setValue(0); + getField("Current").setValue(0); + getField("PeakCurrent").setValue(0); + getField("AvgCurrent").setValue(0); + getField("ConsumedEnergy").setValue(0); + getField("EstimatedFlightTime").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatteryState obj = new FlightBatteryState(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatteryState GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatteryState)(objMngr.getObject(FlightBatteryState.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x791A50E; + protected static final String NAME = "FlightBatteryState"; + protected static String DESCRIPTION = "Battery status information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java new file mode 100644 index 000000000..2e453eda5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Control the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Control the flight plan script + +generated from flightplancontrol.xml + **/ +public class FlightPlanControl extends UAVDataObject { + + public FlightPlanControl() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + List CommandEnumOptions = new ArrayList(); + CommandEnumOptions.add("Start"); + CommandEnumOptions.add("Stop"); + CommandEnumOptions.add("Kill"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.ENUM, CommandElemNames, CommandEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Command").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanControl obj = new FlightPlanControl(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanControl GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanControl)(objMngr.getObject(FlightPlanControl.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x6B4FE6DA; + protected static final String NAME = "FlightPlanControl"; + protected static String DESCRIPTION = "Control the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java new file mode 100644 index 000000000..383e4aff0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -0,0 +1,140 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the flight plan module, control the execution of the script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the flight plan module, control the execution of the script + +generated from flightplansettings.xml + **/ +public class FlightPlanSettings extends UAVDataObject { + + public FlightPlanSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List TestElemNames = new ArrayList(); + TestElemNames.add("0"); + fields.add( new UAVObjectField("Test", "", UAVObjectField.FieldType.FLOAT32, TestElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Test").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanSettings obj = new FlightPlanSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanSettings)(objMngr.getObject(FlightPlanSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x85368422; + protected static final String NAME = "FlightPlanSettings"; + protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java new file mode 100644 index 000000000..00920553c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status of the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status of the flight plan script + +generated from flightplanstatus.xml + **/ +public class FlightPlanStatus extends UAVDataObject { + + public FlightPlanStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Stopped"); + StatusEnumOptions.add("Running"); + StatusEnumOptions.add("Error"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List ErrorTypeElemNames = new ArrayList(); + ErrorTypeElemNames.add("0"); + List ErrorTypeEnumOptions = new ArrayList(); + ErrorTypeEnumOptions.add("None"); + ErrorTypeEnumOptions.add("VMInitError"); + ErrorTypeEnumOptions.add("Exception"); + ErrorTypeEnumOptions.add("IOError"); + ErrorTypeEnumOptions.add("DivByZero"); + ErrorTypeEnumOptions.add("AssertError"); + ErrorTypeEnumOptions.add("AttributeError"); + ErrorTypeEnumOptions.add("ImportError"); + ErrorTypeEnumOptions.add("IndexError"); + ErrorTypeEnumOptions.add("KeyError"); + ErrorTypeEnumOptions.add("MemoryError"); + ErrorTypeEnumOptions.add("NameError"); + ErrorTypeEnumOptions.add("SyntaxError"); + ErrorTypeEnumOptions.add("SystemError"); + ErrorTypeEnumOptions.add("TypeError"); + ErrorTypeEnumOptions.add("ValueError"); + ErrorTypeEnumOptions.add("StopIteration"); + ErrorTypeEnumOptions.add("Warning"); + ErrorTypeEnumOptions.add("UnknownError"); + fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); + + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List Debug1ElemNames = new ArrayList(); + Debug1ElemNames.add("0"); + fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); + + List Debug2ElemNames = new ArrayList(); + Debug2ElemNames.add("0"); + fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Status").setValue(0); + getField("ErrorType").setValue(0); + getField("Debug1").setValue(0); + getField("Debug2").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanStatus obj = new FlightPlanStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanStatus)(objMngr.getObject(FlightPlanStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9FC14812; + protected static final String NAME = "FlightPlanStatus"; + protected static String DESCRIPTION = "Status of the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java new file mode 100644 index 000000000..b58fe6d46 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains the telemetry statistics from the OpenPilot flight computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains the telemetry statistics from the OpenPilot flight computer. + +generated from flighttelemetrystats.xml + **/ +public class FlightTelemetryStats extends UAVDataObject { + + public FlightTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightTelemetryStats obj = new FlightTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightTelemetryStats)(objMngr.getObject(FlightTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x660C265E; + protected static final String NAME = "FlightTelemetryStats"; + protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java new file mode 100644 index 000000000..0f304d45d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The telemetry statistics from the ground computer + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The telemetry statistics from the ground computer + +generated from gcstelemetrystats.xml + **/ +public class GCSTelemetryStats extends UAVDataObject { + + public GCSTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.gcsTelemetryUpdatePeriod = 5000; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSTelemetryStats obj = new GCSTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSTelemetryStats)(objMngr.getObject(GCSTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x771E1046; + protected static final String NAME = "GCSTelemetryStats"; + protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java new file mode 100644 index 000000000..889091e0e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + +generated from gpsposition.xml + **/ +public class GPSPosition extends UAVDataObject { + + public GPSPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "meters", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List GeoidSeparationElemNames = new ArrayList(); + GeoidSeparationElemNames.add("0"); + fields.add( new UAVObjectField("GeoidSeparation", "meters", UAVObjectField.FieldType.FLOAT32, GeoidSeparationElemNames, null) ); + + List HeadingElemNames = new ArrayList(); + HeadingElemNames.add("0"); + fields.add( new UAVObjectField("Heading", "degrees", UAVObjectField.FieldType.FLOAT32, HeadingElemNames, null) ); + + List GroundspeedElemNames = new ArrayList(); + GroundspeedElemNames.add("0"); + fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + + List PDOPElemNames = new ArrayList(); + PDOPElemNames.add("0"); + fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); + + List HDOPElemNames = new ArrayList(); + HDOPElemNames.add("0"); + fields.add( new UAVObjectField("HDOP", "", UAVObjectField.FieldType.FLOAT32, HDOPElemNames, null) ); + + List VDOPElemNames = new ArrayList(); + VDOPElemNames.add("0"); + fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSPosition obj = new GPSPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSPosition)(objMngr.getObject(GPSPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xB5495042; + protected static final String NAME = "GPSPosition"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java new file mode 100644 index 000000000..fa1100207 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -0,0 +1,215 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains information about the GPS satellites in view from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains information about the GPS satellites in view from @ref GPSModule. + +generated from gpssatellites.xml + **/ +public class GPSSatellites extends UAVDataObject { + + public GPSSatellites() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + + List ElevationElemNames = new ArrayList(); + ElevationElemNames.add("0"); + ElevationElemNames.add("1"); + ElevationElemNames.add("2"); + ElevationElemNames.add("3"); + ElevationElemNames.add("4"); + ElevationElemNames.add("5"); + ElevationElemNames.add("6"); + ElevationElemNames.add("7"); + ElevationElemNames.add("8"); + ElevationElemNames.add("9"); + ElevationElemNames.add("10"); + ElevationElemNames.add("11"); + ElevationElemNames.add("12"); + ElevationElemNames.add("13"); + ElevationElemNames.add("14"); + ElevationElemNames.add("15"); + fields.add( new UAVObjectField("Elevation", "degrees", UAVObjectField.FieldType.FLOAT32, ElevationElemNames, null) ); + + List AzimuthElemNames = new ArrayList(); + AzimuthElemNames.add("0"); + AzimuthElemNames.add("1"); + AzimuthElemNames.add("2"); + AzimuthElemNames.add("3"); + AzimuthElemNames.add("4"); + AzimuthElemNames.add("5"); + AzimuthElemNames.add("6"); + AzimuthElemNames.add("7"); + AzimuthElemNames.add("8"); + AzimuthElemNames.add("9"); + AzimuthElemNames.add("10"); + AzimuthElemNames.add("11"); + AzimuthElemNames.add("12"); + AzimuthElemNames.add("13"); + AzimuthElemNames.add("14"); + AzimuthElemNames.add("15"); + fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + + List SNRElemNames = new ArrayList(); + SNRElemNames.add("0"); + SNRElemNames.add("1"); + SNRElemNames.add("2"); + SNRElemNames.add("3"); + SNRElemNames.add("4"); + SNRElemNames.add("5"); + SNRElemNames.add("6"); + SNRElemNames.add("7"); + SNRElemNames.add("8"); + SNRElemNames.add("9"); + SNRElemNames.add("10"); + SNRElemNames.add("11"); + SNRElemNames.add("12"); + SNRElemNames.add("13"); + SNRElemNames.add("14"); + SNRElemNames.add("15"); + fields.add( new UAVObjectField("SNR", "", UAVObjectField.FieldType.INT8, SNRElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSatellites obj = new GPSSatellites(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSatellites GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSatellites)(objMngr.getObject(GPSSatellites.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD62FA3AE; + protected static final String NAME = "GPSSatellites"; + protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java new file mode 100644 index 000000000..5ff55cc2e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + +generated from gpstime.xml + **/ +public class GPSTime extends UAVDataObject { + + public GPSTime() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MonthElemNames = new ArrayList(); + MonthElemNames.add("0"); + fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); + + List DayElemNames = new ArrayList(); + DayElemNames.add("0"); + fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); + + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + + List HourElemNames = new ArrayList(); + HourElemNames.add("0"); + fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); + + List MinuteElemNames = new ArrayList(); + MinuteElemNames.add("0"); + fields.add( new UAVObjectField("Minute", "", UAVObjectField.FieldType.INT8, MinuteElemNames, null) ); + + List SecondElemNames = new ArrayList(); + SecondElemNames.add("0"); + fields.add( new UAVObjectField("Second", "", UAVObjectField.FieldType.INT8, SecondElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSTime obj = new GPSTime(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSTime GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSTime)(objMngr.getObject(GPSTime.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x56FFF0A2; + protected static final String NAME = "GPSTime"; + protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java new file mode 100644 index 000000000..2cde12f64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref GuidanceModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref GuidanceModule + +generated from guidancesettings.xml + **/ +public class GuidanceSettings extends UAVDataObject { + + public GuidanceSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List HorizontalPElemNames = new ArrayList(); + HorizontalPElemNames.add("Kp"); + HorizontalPElemNames.add("Max"); + fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPElemNames = new ArrayList(); + VerticalPElemNames.add("Kp"); + VerticalPElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("GuidanceMode").setValue(0); + getField("HorizontalP").setValue(0.2,0); + getField("HorizontalP").setValue(150,1); + getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalVelPID").setValue(0.002,1); + getField("HorizontalVelPID").setValue(0,2); + getField("HorizontalVelPID").setValue(1000,3); + getField("VerticalP").setValue(0.1,0); + getField("VerticalP").setValue(200,1); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("ThrottleControl").setValue(0); + getField("MaxRollPitch").setValue(10); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GuidanceSettings obj = new GuidanceSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x74740AA2; + protected static final String NAME = "GuidanceSettings"; + protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java new file mode 100644 index 000000000..2adebce70 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + +generated from homelocation.xml + **/ +public class HomeLocation extends UAVDataObject { + + public HomeLocation() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List ECEFElemNames = new ArrayList(); + ECEFElemNames.add("0"); + ECEFElemNames.add("1"); + ECEFElemNames.add("2"); + fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); + + List RNEElemNames = new ArrayList(); + RNEElemNames.add("0"); + RNEElemNames.add("1"); + RNEElemNames.add("2"); + RNEElemNames.add("3"); + RNEElemNames.add("4"); + RNEElemNames.add("5"); + RNEElemNames.add("6"); + RNEElemNames.add("7"); + RNEElemNames.add("8"); + fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); + + List BeElemNames = new ArrayList(); + BeElemNames.add("0"); + BeElemNames.add("1"); + BeElemNames.add("2"); + fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Set").setValue(0); + getField("Latitude").setValue(0); + getField("Longitude").setValue(0); + getField("Altitude").setValue(0); + getField("ECEF").setValue(0,0); + getField("ECEF").setValue(0,1); + getField("ECEF").setValue(0,2); + getField("RNE").setValue(0,0); + getField("RNE").setValue(0,1); + getField("RNE").setValue(0,2); + getField("RNE").setValue(0,3); + getField("RNE").setValue(0,4); + getField("RNE").setValue(0,5); + getField("RNE").setValue(0,6); + getField("RNE").setValue(0,7); + getField("RNE").setValue(0,8); + getField("Be").setValue(0,0); + getField("Be").setValue(0,1); + getField("Be").setValue(0,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HomeLocation obj = new HomeLocation(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HomeLocation GetInstance(UAVObjectManager objMngr, int instID) + { + return (HomeLocation)(objMngr.getObject(HomeLocation.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD6008ED2; + protected static final String NAME = "HomeLocation"; + protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java new file mode 100644 index 000000000..fc68e2902 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -0,0 +1,238 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Tracks statistics on the I2C bus. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Tracks statistics on the I2C bus. + +generated from i2cstats.xml + **/ +public class I2CStats extends UAVDataObject { + + public I2CStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List event_errorsElemNames = new ArrayList(); + event_errorsElemNames.add("0"); + fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); + + List fsm_errorsElemNames = new ArrayList(); + fsm_errorsElemNames.add("0"); + fields.add( new UAVObjectField("fsm_errors", "", UAVObjectField.FieldType.UINT8, fsm_errorsElemNames, null) ); + + List irq_errorsElemNames = new ArrayList(); + irq_errorsElemNames.add("0"); + fields.add( new UAVObjectField("irq_errors", "", UAVObjectField.FieldType.UINT8, irq_errorsElemNames, null) ); + + List nacksElemNames = new ArrayList(); + nacksElemNames.add("0"); + fields.add( new UAVObjectField("nacks", "", UAVObjectField.FieldType.UINT8, nacksElemNames, null) ); + + List timeoutsElemNames = new ArrayList(); + timeoutsElemNames.add("0"); + fields.add( new UAVObjectField("timeouts", "", UAVObjectField.FieldType.UINT8, timeoutsElemNames, null) ); + + List last_error_typeElemNames = new ArrayList(); + last_error_typeElemNames.add("0"); + List last_error_typeEnumOptions = new ArrayList(); + last_error_typeEnumOptions.add("EVENT"); + last_error_typeEnumOptions.add("FSM"); + last_error_typeEnumOptions.add("INTERRUPT"); + fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); + + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + + List event_logElemNames = new ArrayList(); + event_logElemNames.add("0"); + event_logElemNames.add("1"); + event_logElemNames.add("2"); + event_logElemNames.add("3"); + event_logElemNames.add("4"); + List event_logEnumOptions = new ArrayList(); + event_logEnumOptions.add("I2C_EVENT_BUS_ERROR"); + event_logEnumOptions.add("I2C_EVENT_START"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_NACK"); + event_logEnumOptions.add("I2C_EVENT_STOPPED"); + event_logEnumOptions.add("I2C_EVENT_AUTO"); + fields.add( new UAVObjectField("event_log", "", UAVObjectField.FieldType.ENUM, event_logElemNames, event_logEnumOptions) ); + + List state_logElemNames = new ArrayList(); + state_logElemNames.add("0"); + state_logElemNames.add("1"); + state_logElemNames.add("2"); + state_logElemNames.add("3"); + state_logElemNames.add("4"); + List state_logEnumOptions = new ArrayList(); + state_logEnumOptions.add("I2C_STATE_FSM_FAULT"); + state_logEnumOptions.add("I2C_STATE_BUS_ERROR"); + state_logEnumOptions.add("I2C_STATE_STOPPED"); + state_logEnumOptions.add("I2C_STATE_STOPPING"); + state_logEnumOptions.add("I2C_STATE_STARTING"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_POST_LAST"); + state_logEnumOptions.add("R_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_LAST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_POST_LAST"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_NACK"); + fields.add( new UAVObjectField("state_log", "", UAVObjectField.FieldType.ENUM, state_logElemNames, state_logEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + I2CStats obj = new I2CStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public I2CStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (I2CStats)(objMngr.getObject(I2CStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x23CE9E9C; + protected static final String NAME = "I2CStats"; + protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java new file mode 100644 index 000000000..636f30946 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -0,0 +1,199 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + +generated from manualcontrolcommand.xml + **/ +public class ManualControlCommand extends UAVDataObject { + + public ManualControlCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("False"); + ArmedEnumOptions.add("True"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlCommand obj = new ManualControlCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlCommand)(objMngr.getObject(ManualControlCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x926794; + protected static final String NAME = "ManualControlCommand"; + protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java new file mode 100644 index 000000000..c14aef758 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -0,0 +1,395 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to indicate how to decode receiver input by @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to indicate how to decode receiver input by @ref ManualControlModule. + +generated from manualcontrolsettings.xml + **/ +public class ManualControlSettings extends UAVDataObject { + + public ManualControlSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List InputModeElemNames = new ArrayList(); + InputModeElemNames.add("0"); + List InputModeEnumOptions = new ArrayList(); + InputModeEnumOptions.add("PWM"); + InputModeEnumOptions.add("PPM"); + InputModeEnumOptions.add("Spektrum"); + fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + List RollEnumOptions = new ArrayList(); + RollEnumOptions.add("Channel1"); + RollEnumOptions.add("Channel2"); + RollEnumOptions.add("Channel3"); + RollEnumOptions.add("Channel4"); + RollEnumOptions.add("Channel5"); + RollEnumOptions.add("Channel6"); + RollEnumOptions.add("Channel7"); + RollEnumOptions.add("Channel8"); + RollEnumOptions.add("None"); + fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + List PitchEnumOptions = new ArrayList(); + PitchEnumOptions.add("Channel1"); + PitchEnumOptions.add("Channel2"); + PitchEnumOptions.add("Channel3"); + PitchEnumOptions.add("Channel4"); + PitchEnumOptions.add("Channel5"); + PitchEnumOptions.add("Channel6"); + PitchEnumOptions.add("Channel7"); + PitchEnumOptions.add("Channel8"); + PitchEnumOptions.add("None"); + fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + List YawEnumOptions = new ArrayList(); + YawEnumOptions.add("Channel1"); + YawEnumOptions.add("Channel2"); + YawEnumOptions.add("Channel3"); + YawEnumOptions.add("Channel4"); + YawEnumOptions.add("Channel5"); + YawEnumOptions.add("Channel6"); + YawEnumOptions.add("Channel7"); + YawEnumOptions.add("Channel8"); + YawEnumOptions.add("None"); + fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + List ThrottleEnumOptions = new ArrayList(); + ThrottleEnumOptions.add("Channel1"); + ThrottleEnumOptions.add("Channel2"); + ThrottleEnumOptions.add("Channel3"); + ThrottleEnumOptions.add("Channel4"); + ThrottleEnumOptions.add("Channel5"); + ThrottleEnumOptions.add("Channel6"); + ThrottleEnumOptions.add("Channel7"); + ThrottleEnumOptions.add("Channel8"); + ThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Channel1"); + FlightModeEnumOptions.add("Channel2"); + FlightModeEnumOptions.add("Channel3"); + FlightModeEnumOptions.add("Channel4"); + FlightModeEnumOptions.add("Channel5"); + FlightModeEnumOptions.add("Channel6"); + FlightModeEnumOptions.add("Channel7"); + FlightModeEnumOptions.add("Channel8"); + FlightModeEnumOptions.add("None"); + fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + List Accessory1EnumOptions = new ArrayList(); + Accessory1EnumOptions.add("Channel1"); + Accessory1EnumOptions.add("Channel2"); + Accessory1EnumOptions.add("Channel3"); + Accessory1EnumOptions.add("Channel4"); + Accessory1EnumOptions.add("Channel5"); + Accessory1EnumOptions.add("Channel6"); + Accessory1EnumOptions.add("Channel7"); + Accessory1EnumOptions.add("Channel8"); + Accessory1EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + List Accessory2EnumOptions = new ArrayList(); + Accessory2EnumOptions.add("Channel1"); + Accessory2EnumOptions.add("Channel2"); + Accessory2EnumOptions.add("Channel3"); + Accessory2EnumOptions.add("Channel4"); + Accessory2EnumOptions.add("Channel5"); + Accessory2EnumOptions.add("Channel6"); + Accessory2EnumOptions.add("Channel7"); + Accessory2EnumOptions.add("Channel8"); + Accessory2EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + List Accessory3EnumOptions = new ArrayList(); + Accessory3EnumOptions.add("Channel1"); + Accessory3EnumOptions.add("Channel2"); + Accessory3EnumOptions.add("Channel3"); + Accessory3EnumOptions.add("Channel4"); + Accessory3EnumOptions.add("Channel5"); + Accessory3EnumOptions.add("Channel6"); + Accessory3EnumOptions.add("Channel7"); + Accessory3EnumOptions.add("Channel8"); + Accessory3EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + + List ArmingElemNames = new ArrayList(); + ArmingElemNames.add("0"); + List ArmingEnumOptions = new ArrayList(); + ArmingEnumOptions.add("Always Disarmed"); + ArmingEnumOptions.add("Always Armed"); + ArmingEnumOptions.add("Roll Left"); + ArmingEnumOptions.add("Roll Right"); + ArmingEnumOptions.add("Pitch Forward"); + ArmingEnumOptions.add("Pitch Aft"); + ArmingEnumOptions.add("Yaw Left"); + ArmingEnumOptions.add("Yaw Right"); + fields.add( new UAVObjectField("Arming", "", UAVObjectField.FieldType.ENUM, ArmingElemNames, ArmingEnumOptions) ); + + List Stabilization1SettingsElemNames = new ArrayList(); + Stabilization1SettingsElemNames.add("Roll"); + Stabilization1SettingsElemNames.add("Pitch"); + Stabilization1SettingsElemNames.add("Yaw"); + List Stabilization1SettingsEnumOptions = new ArrayList(); + Stabilization1SettingsEnumOptions.add("None"); + Stabilization1SettingsEnumOptions.add("Rate"); + Stabilization1SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); + + List Stabilization2SettingsElemNames = new ArrayList(); + Stabilization2SettingsElemNames.add("Roll"); + Stabilization2SettingsElemNames.add("Pitch"); + Stabilization2SettingsElemNames.add("Yaw"); + List Stabilization2SettingsEnumOptions = new ArrayList(); + Stabilization2SettingsEnumOptions.add("None"); + Stabilization2SettingsEnumOptions.add("Rate"); + Stabilization2SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); + + List Stabilization3SettingsElemNames = new ArrayList(); + Stabilization3SettingsElemNames.add("Roll"); + Stabilization3SettingsElemNames.add("Pitch"); + Stabilization3SettingsElemNames.add("Yaw"); + List Stabilization3SettingsEnumOptions = new ArrayList(); + Stabilization3SettingsEnumOptions.add("None"); + Stabilization3SettingsEnumOptions.add("Rate"); + Stabilization3SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); + + List FlightModePositionElemNames = new ArrayList(); + FlightModePositionElemNames.add("0"); + FlightModePositionElemNames.add("1"); + FlightModePositionElemNames.add("2"); + List FlightModePositionEnumOptions = new ArrayList(); + FlightModePositionEnumOptions.add("Manual"); + FlightModePositionEnumOptions.add("Stabilized1"); + FlightModePositionEnumOptions.add("Stabilized2"); + FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("VelocityControl"); + FlightModePositionEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("InputMode").setValue(0); + getField("Roll").setValue(0); + getField("Pitch").setValue(1); + getField("Yaw").setValue(2); + getField("Throttle").setValue(3); + getField("FlightMode").setValue(4); + getField("Accessory1").setValue(8); + getField("Accessory2").setValue(8); + getField("Accessory3").setValue(8); + getField("Arming").setValue(0); + getField("Stabilization1Settings").setValue(2,0); + getField("Stabilization1Settings").setValue(2,1); + getField("Stabilization1Settings").setValue(2,2); + getField("Stabilization2Settings").setValue(2,0); + getField("Stabilization2Settings").setValue(2,1); + getField("Stabilization2Settings").setValue(2,2); + getField("Stabilization3Settings").setValue(2,0); + getField("Stabilization3Settings").setValue(2,1); + getField("Stabilization3Settings").setValue(2,2); + getField("FlightModePosition").setValue(0,0); + getField("FlightModePosition").setValue(1,1); + getField("FlightModePosition").setValue(2,2); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ArmedTimeout").setValue(30000); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlSettings obj = new ManualControlSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlSettings)(objMngr.getObject(ManualControlSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2B82102; + protected static final String NAME = "ManualControlSettings"; + protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java new file mode 100644 index 000000000..554e366f3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -0,0 +1,357 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from mixersettings.xml + **/ +public class MixerSettings extends UAVDataObject { + + public MixerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAccelElemNames = new ArrayList(); + MaxAccelElemNames.add("0"); + fields.add( new UAVObjectField("MaxAccel", "units/sec", UAVObjectField.FieldType.FLOAT32, MaxAccelElemNames, null) ); + + List FeedForwardElemNames = new ArrayList(); + FeedForwardElemNames.add("0"); + fields.add( new UAVObjectField("FeedForward", "", UAVObjectField.FieldType.FLOAT32, FeedForwardElemNames, null) ); + + List AccelTimeElemNames = new ArrayList(); + AccelTimeElemNames.add("0"); + fields.add( new UAVObjectField("AccelTime", "ms", UAVObjectField.FieldType.FLOAT32, AccelTimeElemNames, null) ); + + List DecelTimeElemNames = new ArrayList(); + DecelTimeElemNames.add("0"); + fields.add( new UAVObjectField("DecelTime", "ms", UAVObjectField.FieldType.FLOAT32, DecelTimeElemNames, null) ); + + List ThrottleCurve1ElemNames = new ArrayList(); + ThrottleCurve1ElemNames.add("0"); + ThrottleCurve1ElemNames.add("25"); + ThrottleCurve1ElemNames.add("50"); + ThrottleCurve1ElemNames.add("75"); + ThrottleCurve1ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve1", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve1ElemNames, null) ); + + List ThrottleCurve2ElemNames = new ArrayList(); + ThrottleCurve2ElemNames.add("0"); + ThrottleCurve2ElemNames.add("25"); + ThrottleCurve2ElemNames.add("50"); + ThrottleCurve2ElemNames.add("75"); + ThrottleCurve2ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + + List Mixer1TypeElemNames = new ArrayList(); + Mixer1TypeElemNames.add("0"); + List Mixer1TypeEnumOptions = new ArrayList(); + Mixer1TypeEnumOptions.add("Disabled"); + Mixer1TypeEnumOptions.add("Motor"); + Mixer1TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); + + List Mixer1VectorElemNames = new ArrayList(); + Mixer1VectorElemNames.add("ThrottleCurve1"); + Mixer1VectorElemNames.add("ThrottleCurve2"); + Mixer1VectorElemNames.add("Roll"); + Mixer1VectorElemNames.add("Pitch"); + Mixer1VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer1Vector", "", UAVObjectField.FieldType.INT8, Mixer1VectorElemNames, null) ); + + List Mixer2TypeElemNames = new ArrayList(); + Mixer2TypeElemNames.add("0"); + List Mixer2TypeEnumOptions = new ArrayList(); + Mixer2TypeEnumOptions.add("Disabled"); + Mixer2TypeEnumOptions.add("Motor"); + Mixer2TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); + + List Mixer2VectorElemNames = new ArrayList(); + Mixer2VectorElemNames.add("ThrottleCurve1"); + Mixer2VectorElemNames.add("ThrottleCurve2"); + Mixer2VectorElemNames.add("Roll"); + Mixer2VectorElemNames.add("Pitch"); + Mixer2VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer2Vector", "", UAVObjectField.FieldType.INT8, Mixer2VectorElemNames, null) ); + + List Mixer3TypeElemNames = new ArrayList(); + Mixer3TypeElemNames.add("0"); + List Mixer3TypeEnumOptions = new ArrayList(); + Mixer3TypeEnumOptions.add("Disabled"); + Mixer3TypeEnumOptions.add("Motor"); + Mixer3TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); + + List Mixer3VectorElemNames = new ArrayList(); + Mixer3VectorElemNames.add("ThrottleCurve1"); + Mixer3VectorElemNames.add("ThrottleCurve2"); + Mixer3VectorElemNames.add("Roll"); + Mixer3VectorElemNames.add("Pitch"); + Mixer3VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer3Vector", "", UAVObjectField.FieldType.INT8, Mixer3VectorElemNames, null) ); + + List Mixer4TypeElemNames = new ArrayList(); + Mixer4TypeElemNames.add("0"); + List Mixer4TypeEnumOptions = new ArrayList(); + Mixer4TypeEnumOptions.add("Disabled"); + Mixer4TypeEnumOptions.add("Motor"); + Mixer4TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); + + List Mixer4VectorElemNames = new ArrayList(); + Mixer4VectorElemNames.add("ThrottleCurve1"); + Mixer4VectorElemNames.add("ThrottleCurve2"); + Mixer4VectorElemNames.add("Roll"); + Mixer4VectorElemNames.add("Pitch"); + Mixer4VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer4Vector", "", UAVObjectField.FieldType.INT8, Mixer4VectorElemNames, null) ); + + List Mixer5TypeElemNames = new ArrayList(); + Mixer5TypeElemNames.add("0"); + List Mixer5TypeEnumOptions = new ArrayList(); + Mixer5TypeEnumOptions.add("Disabled"); + Mixer5TypeEnumOptions.add("Motor"); + Mixer5TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); + + List Mixer5VectorElemNames = new ArrayList(); + Mixer5VectorElemNames.add("ThrottleCurve1"); + Mixer5VectorElemNames.add("ThrottleCurve2"); + Mixer5VectorElemNames.add("Roll"); + Mixer5VectorElemNames.add("Pitch"); + Mixer5VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer5Vector", "", UAVObjectField.FieldType.INT8, Mixer5VectorElemNames, null) ); + + List Mixer6TypeElemNames = new ArrayList(); + Mixer6TypeElemNames.add("0"); + List Mixer6TypeEnumOptions = new ArrayList(); + Mixer6TypeEnumOptions.add("Disabled"); + Mixer6TypeEnumOptions.add("Motor"); + Mixer6TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); + + List Mixer6VectorElemNames = new ArrayList(); + Mixer6VectorElemNames.add("ThrottleCurve1"); + Mixer6VectorElemNames.add("ThrottleCurve2"); + Mixer6VectorElemNames.add("Roll"); + Mixer6VectorElemNames.add("Pitch"); + Mixer6VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer6Vector", "", UAVObjectField.FieldType.INT8, Mixer6VectorElemNames, null) ); + + List Mixer7TypeElemNames = new ArrayList(); + Mixer7TypeElemNames.add("0"); + List Mixer7TypeEnumOptions = new ArrayList(); + Mixer7TypeEnumOptions.add("Disabled"); + Mixer7TypeEnumOptions.add("Motor"); + Mixer7TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); + + List Mixer7VectorElemNames = new ArrayList(); + Mixer7VectorElemNames.add("ThrottleCurve1"); + Mixer7VectorElemNames.add("ThrottleCurve2"); + Mixer7VectorElemNames.add("Roll"); + Mixer7VectorElemNames.add("Pitch"); + Mixer7VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer7Vector", "", UAVObjectField.FieldType.INT8, Mixer7VectorElemNames, null) ); + + List Mixer8TypeElemNames = new ArrayList(); + Mixer8TypeElemNames.add("0"); + List Mixer8TypeEnumOptions = new ArrayList(); + Mixer8TypeEnumOptions.add("Disabled"); + Mixer8TypeEnumOptions.add("Motor"); + Mixer8TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); + + List Mixer8VectorElemNames = new ArrayList(); + Mixer8VectorElemNames.add("ThrottleCurve1"); + Mixer8VectorElemNames.add("ThrottleCurve2"); + Mixer8VectorElemNames.add("Roll"); + Mixer8VectorElemNames.add("Pitch"); + Mixer8VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAccel").setValue(1000); + getField("FeedForward").setValue(0); + getField("AccelTime").setValue(0); + getField("DecelTime").setValue(0); + getField("ThrottleCurve1").setValue(0,0); + getField("ThrottleCurve1").setValue(0.25,1); + getField("ThrottleCurve1").setValue(0.5,2); + getField("ThrottleCurve1").setValue(0.75,3); + getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve2").setValue(0,0); + getField("ThrottleCurve2").setValue(0.25,1); + getField("ThrottleCurve2").setValue(0.5,2); + getField("ThrottleCurve2").setValue(0.75,3); + getField("ThrottleCurve2").setValue(1,4); + getField("Mixer1Type").setValue(0); + getField("Mixer1Vector").setValue(0,0); + getField("Mixer1Vector").setValue(0,1); + getField("Mixer1Vector").setValue(0,2); + getField("Mixer1Vector").setValue(0,3); + getField("Mixer1Vector").setValue(0,4); + getField("Mixer2Type").setValue(0); + getField("Mixer2Vector").setValue(0,0); + getField("Mixer2Vector").setValue(0,1); + getField("Mixer2Vector").setValue(0,2); + getField("Mixer2Vector").setValue(0,3); + getField("Mixer2Vector").setValue(0,4); + getField("Mixer3Type").setValue(0); + getField("Mixer3Vector").setValue(0,0); + getField("Mixer3Vector").setValue(0,1); + getField("Mixer3Vector").setValue(0,2); + getField("Mixer3Vector").setValue(0,3); + getField("Mixer3Vector").setValue(0,4); + getField("Mixer4Type").setValue(0); + getField("Mixer4Vector").setValue(0,0); + getField("Mixer4Vector").setValue(0,1); + getField("Mixer4Vector").setValue(0,2); + getField("Mixer4Vector").setValue(0,3); + getField("Mixer4Vector").setValue(0,4); + getField("Mixer5Type").setValue(0); + getField("Mixer5Vector").setValue(0,0); + getField("Mixer5Vector").setValue(0,1); + getField("Mixer5Vector").setValue(0,2); + getField("Mixer5Vector").setValue(0,3); + getField("Mixer5Vector").setValue(0,4); + getField("Mixer6Type").setValue(0); + getField("Mixer6Vector").setValue(0,0); + getField("Mixer6Vector").setValue(0,1); + getField("Mixer6Vector").setValue(0,2); + getField("Mixer6Vector").setValue(0,3); + getField("Mixer6Vector").setValue(0,4); + getField("Mixer7Type").setValue(0); + getField("Mixer7Vector").setValue(0,0); + getField("Mixer7Vector").setValue(0,1); + getField("Mixer7Vector").setValue(0,2); + getField("Mixer7Vector").setValue(0,3); + getField("Mixer7Vector").setValue(0,4); + getField("Mixer8Type").setValue(0); + getField("Mixer8Vector").setValue(0,0); + getField("Mixer8Vector").setValue(0,1); + getField("Mixer8Vector").setValue(0,2); + getField("Mixer8Vector").setValue(0,3); + getField("Mixer8Vector").setValue(0,4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerSettings obj = new MixerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerSettings)(objMngr.getObject(MixerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4FAE374E; + protected static final String NAME = "MixerSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java new file mode 100644 index 000000000..fbd405b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -0,0 +1,167 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from mixerstatus.xml + **/ +public class MixerStatus extends UAVDataObject { + + public MixerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List Mixer1ElemNames = new ArrayList(); + Mixer1ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer1", "", UAVObjectField.FieldType.FLOAT32, Mixer1ElemNames, null) ); + + List Mixer2ElemNames = new ArrayList(); + Mixer2ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer2", "", UAVObjectField.FieldType.FLOAT32, Mixer2ElemNames, null) ); + + List Mixer3ElemNames = new ArrayList(); + Mixer3ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer3", "", UAVObjectField.FieldType.FLOAT32, Mixer3ElemNames, null) ); + + List Mixer4ElemNames = new ArrayList(); + Mixer4ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer4", "", UAVObjectField.FieldType.FLOAT32, Mixer4ElemNames, null) ); + + List Mixer5ElemNames = new ArrayList(); + Mixer5ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer5", "", UAVObjectField.FieldType.FLOAT32, Mixer5ElemNames, null) ); + + List Mixer6ElemNames = new ArrayList(); + Mixer6ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer6", "", UAVObjectField.FieldType.FLOAT32, Mixer6ElemNames, null) ); + + List Mixer7ElemNames = new ArrayList(); + Mixer7ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer7", "", UAVObjectField.FieldType.FLOAT32, Mixer7ElemNames, null) ); + + List Mixer8ElemNames = new ArrayList(); + Mixer8ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerStatus obj = new MixerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerStatus)(objMngr.getObject(MixerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF6A33F10; + protected static final String NAME = "MixerStatus"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java new file mode 100644 index 000000000..f16ddd199 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The projection of acceleration in the NED reference frame used by @ref Guidance. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The projection of acceleration in the NED reference frame used by @ref Guidance. + +generated from nedaccel.xml + **/ +public class NedAccel extends UAVDataObject { + + public NedAccel() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10001; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NedAccel obj = new NedAccel(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NedAccel GetInstance(UAVObjectManager objMngr, int instID) + { + return (NedAccel)(objMngr.getObject(NedAccel.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8E852CE8; + protected static final String NAME = "NedAccel"; + protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java new file mode 100644 index 000000000..2a09c2b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -0,0 +1,160 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Someone who knows please enter this + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Someone who knows please enter this + +generated from objectpersistence.xml + **/ +public class ObjectPersistence extends UAVDataObject { + + public ObjectPersistence() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List OperationElemNames = new ArrayList(); + OperationElemNames.add("0"); + List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("Load"); + OperationEnumOptions.add("Save"); + OperationEnumOptions.add("Delete"); + fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); + + List SelectionElemNames = new ArrayList(); + SelectionElemNames.add("0"); + List SelectionEnumOptions = new ArrayList(); + SelectionEnumOptions.add("SingleObject"); + SelectionEnumOptions.add("AllSettings"); + SelectionEnumOptions.add("AllMetaObjects"); + SelectionEnumOptions.add("AllObjects"); + fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); + + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ObjectPersistence obj = new ObjectPersistence(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ObjectPersistence GetInstance(UAVObjectManager objMngr, int instID) + { + return (ObjectPersistence)(objMngr.getObject(ObjectPersistence.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x22216832; + protected static final String NAME = "ObjectPersistence"; + protected static String DESCRIPTION = "Someone who knows please enter this"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java new file mode 100644 index 000000000..444009f90 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from positionactual.xml + **/ +public class PositionActual extends UAVDataObject { + + public PositionActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionActual obj = new PositionActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionActual)(objMngr.getObject(PositionActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE0739636; + protected static final String NAME = "PositionActual"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java new file mode 100644 index 000000000..5cf51df71 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + +generated from positiondesired.xml + **/ +public class PositionDesired extends UAVDataObject { + + public PositionDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionDesired obj = new PositionDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2FC4E5BA; + protected static final String NAME = "PositionDesired"; + protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java new file mode 100644 index 000000000..7164c0957 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from ratedesired.xml + **/ +public class RateDesired extends UAVDataObject { + + public RateDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg/s", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg/s", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RateDesired obj = new RateDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RateDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (RateDesired)(objMngr.getObject(RateDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA41B51C; + protected static final String NAME = "RateDesired"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java new file mode 100644 index 000000000..4e9f0b8b8 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the ultrasound sonar sensor with altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the ultrasound sonar sensor with altitude estimate. + +generated from sonaraltitude.xml + **/ +public class SonarAltitude extends UAVDataObject { + + public SonarAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SonarAltitude obj = new SonarAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SonarAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (SonarAltitude)(objMngr.getObject(SonarAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FDD844C; + protected static final String NAME = "SonarAltitude"; + protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java new file mode 100644 index 000000000..8cba8a54c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -0,0 +1,161 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + +generated from stabilizationdesired.xml + **/ +public class StabilizationDesired extends UAVDataObject { + + public StabilizationDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("None"); + StabilizationModeEnumOptions.add("Rate"); + StabilizationModeEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationDesired obj = new StabilizationDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationDesired)(objMngr.getObject(StabilizationDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x41AA9DC2; + protected static final String NAME = "StabilizationDesired"; + protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java new file mode 100644 index 000000000..74c480e1c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -0,0 +1,222 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + +generated from stabilizationsettings.xml + **/ +public class StabilizationSettings extends UAVDataObject { + + public StabilizationSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List ManualRateElemNames = new ArrayList(); + ManualRateElemNames.add("Roll"); + ManualRateElemNames.add("Pitch"); + ManualRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("ManualRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, ManualRateElemNames, null) ); + + List MaximumRateElemNames = new ArrayList(); + MaximumRateElemNames.add("Roll"); + MaximumRateElemNames.add("Pitch"); + MaximumRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); + + List RollRatePIElemNames = new ArrayList(); + RollRatePIElemNames.add("Kp"); + RollRatePIElemNames.add("Ki"); + RollRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + + List PitchRatePIElemNames = new ArrayList(); + PitchRatePIElemNames.add("Kp"); + PitchRatePIElemNames.add("Ki"); + PitchRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + + List YawRatePIElemNames = new ArrayList(); + YawRatePIElemNames.add("Kp"); + YawRatePIElemNames.add("Ki"); + YawRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + + List RollPIElemNames = new ArrayList(); + RollPIElemNames.add("Kp"); + RollPIElemNames.add("Ki"); + RollPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollPI", "", UAVObjectField.FieldType.FLOAT32, RollPIElemNames, null) ); + + List PitchPIElemNames = new ArrayList(); + PitchPIElemNames.add("Kp"); + PitchPIElemNames.add("Ki"); + PitchPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchPI", "", UAVObjectField.FieldType.FLOAT32, PitchPIElemNames, null) ); + + List YawPIElemNames = new ArrayList(); + YawPIElemNames.add("Kp"); + YawPIElemNames.add("Ki"); + YawPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("RollMax").setValue(35); + getField("PitchMax").setValue(35); + getField("YawMax").setValue(35); + getField("ManualRate").setValue(150,0); + getField("ManualRate").setValue(150,1); + getField("ManualRate").setValue(150,2); + getField("MaximumRate").setValue(300,0); + getField("MaximumRate").setValue(300,1); + getField("MaximumRate").setValue(300,2); + getField("RollRatePI").setValue(0.0015,0); + getField("RollRatePI").setValue(0,1); + getField("RollRatePI").setValue(0.3,2); + getField("PitchRatePI").setValue(0.0015,0); + getField("PitchRatePI").setValue(0,1); + getField("PitchRatePI").setValue(0.3,2); + getField("YawRatePI").setValue(0.003,0); + getField("YawRatePI").setValue(0,1); + getField("YawRatePI").setValue(0.3,2); + getField("RollPI").setValue(2,0); + getField("RollPI").setValue(0,1); + getField("RollPI").setValue(50,2); + getField("PitchPI").setValue(2,0); + getField("PitchPI").setValue(0,1); + getField("PitchPI").setValue(50,2); + getField("YawPI").setValue(2,0); + getField("YawPI").setValue(0,1); + getField("YawPI").setValue(50,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationSettings obj = new StabilizationSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationSettings)(objMngr.getObject(StabilizationSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2147404; + protected static final String NAME = "StabilizationSettings"; + protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java new file mode 100644 index 000000000..9136627f4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -0,0 +1,176 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + +generated from systemalarms.xml + **/ +public class SystemAlarms extends UAVDataObject { + + public SystemAlarms() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlarmElemNames = new ArrayList(); + AlarmElemNames.add("OutOfMemory"); + AlarmElemNames.add("StackOverflow"); + AlarmElemNames.add("CPUOverload"); + AlarmElemNames.add("EventSystem"); + AlarmElemNames.add("SDCard"); + AlarmElemNames.add("Telemetry"); + AlarmElemNames.add("ManualControl"); + AlarmElemNames.add("Actuator"); + AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Stabilization"); + AlarmElemNames.add("Guidance"); + AlarmElemNames.add("AHRSComms"); + AlarmElemNames.add("Battery"); + AlarmElemNames.add("FlightTime"); + AlarmElemNames.add("I2C"); + AlarmElemNames.add("GPS"); + List AlarmEnumOptions = new ArrayList(); + AlarmEnumOptions.add("Uninitialised"); + AlarmEnumOptions.add("OK"); + AlarmEnumOptions.add("Warning"); + AlarmEnumOptions.add("Error"); + AlarmEnumOptions.add("Critical"); + fields.add( new UAVObjectField("Alarm", "", UAVObjectField.FieldType.ENUM, AlarmElemNames, AlarmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 4000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Alarm").setValue(0,0); + getField("Alarm").setValue(0,1); + getField("Alarm").setValue(0,2); + getField("Alarm").setValue(0,3); + getField("Alarm").setValue(0,4); + getField("Alarm").setValue(0,5); + getField("Alarm").setValue(0,6); + getField("Alarm").setValue(0,7); + getField("Alarm").setValue(0,8); + getField("Alarm").setValue(0,9); + getField("Alarm").setValue(0,10); + getField("Alarm").setValue(0,11); + getField("Alarm").setValue(0,12); + getField("Alarm").setValue(0,13); + getField("Alarm").setValue(0,14); + getField("Alarm").setValue(0,15); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemAlarms obj = new SystemAlarms(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemAlarms GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemAlarms)(objMngr.getObject(SystemAlarms.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x89C3DCB2; + protected static final String NAME = "SystemAlarms"; + protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java new file mode 100644 index 000000000..d01b55b24 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -0,0 +1,157 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + +generated from systemsettings.xml + **/ +public class SystemSettings extends UAVDataObject { + + public SystemSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirframeTypeElemNames = new ArrayList(); + AirframeTypeElemNames.add("0"); + List AirframeTypeEnumOptions = new ArrayList(); + AirframeTypeEnumOptions.add("FixedWing"); + AirframeTypeEnumOptions.add("FixedWingElevon"); + AirframeTypeEnumOptions.add("FixedWingVtail"); + AirframeTypeEnumOptions.add("VTOL"); + AirframeTypeEnumOptions.add("HeliCP"); + AirframeTypeEnumOptions.add("QuadX"); + AirframeTypeEnumOptions.add("QuadP"); + AirframeTypeEnumOptions.add("Hexa"); + AirframeTypeEnumOptions.add("Octo"); + AirframeTypeEnumOptions.add("Custom"); + AirframeTypeEnumOptions.add("HexaX"); + AirframeTypeEnumOptions.add("OctoV"); + AirframeTypeEnumOptions.add("OctoCoaxP"); + AirframeTypeEnumOptions.add("OctoCoaxX"); + AirframeTypeEnumOptions.add("HexaCoax"); + AirframeTypeEnumOptions.add("Tri"); + fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirframeType").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemSettings obj = new SystemSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemSettings)(objMngr.getObject(SystemSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3875CEE; + protected static final String NAME = "SystemSettings"; + protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java new file mode 100644 index 000000000..7c34360e9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * CPU and memory usage from OpenPilot computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +CPU and memory usage from OpenPilot computer. + +generated from systemstats.xml + **/ +public class SystemStats extends UAVDataObject { + + public SystemStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FlightTimeElemNames = new ArrayList(); + FlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + + List HeapRemainingElemNames = new ArrayList(); + HeapRemainingElemNames.add("0"); + fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List CPUTempElemNames = new ArrayList(); + CPUTempElemNames.add("0"); + fields.add( new UAVObjectField("CPUTemp", "C", UAVObjectField.FieldType.INT8, CPUTempElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemStats obj = new SystemStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemStats)(objMngr.getObject(SystemStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAA26FFFA; + protected static final String NAME = "SystemStats"; + protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java new file mode 100644 index 000000000..3ad065b5c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -0,0 +1,170 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Task information + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Task information + +generated from taskinfo.xml + **/ +public class TaskInfo extends UAVDataObject { + + public TaskInfo() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StackRemainingElemNames = new ArrayList(); + StackRemainingElemNames.add("System"); + StackRemainingElemNames.add("Actuator"); + StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("TelemetryTx"); + StackRemainingElemNames.add("TelemetryTxPri"); + StackRemainingElemNames.add("TelemetryRx"); + StackRemainingElemNames.add("GPS"); + StackRemainingElemNames.add("ManualControl"); + StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("AHRSComms"); + StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("Guidance"); + StackRemainingElemNames.add("FlightPlan"); + fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); + + List RunningElemNames = new ArrayList(); + RunningElemNames.add("System"); + RunningElemNames.add("Actuator"); + RunningElemNames.add("Attitude"); + RunningElemNames.add("TelemetryTx"); + RunningElemNames.add("TelemetryTxPri"); + RunningElemNames.add("TelemetryRx"); + RunningElemNames.add("GPS"); + RunningElemNames.add("ManualControl"); + RunningElemNames.add("Altitude"); + RunningElemNames.add("AHRSComms"); + RunningElemNames.add("Stabilization"); + RunningElemNames.add("Guidance"); + RunningElemNames.add("FlightPlan"); + List RunningEnumOptions = new ArrayList(); + RunningEnumOptions.add("False"); + RunningEnumOptions.add("True"); + fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TaskInfo obj = new TaskInfo(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TaskInfo GetInstance(UAVObjectManager objMngr, int instID) + { + return (TaskInfo)(objMngr.getObject(TaskInfo.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x50F599F0; + protected static final String NAME = "TaskInfo"; + protected static String DESCRIPTION = "Task information"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java new file mode 100644 index 000000000..6995a02b0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select baud rate of telemetry. Warning - this must match your modem. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select baud rate of telemetry. Warning - this must match your modem. + +generated from telemetrysettings.xml + **/ +public class TelemetrySettings extends UAVDataObject { + + public TelemetrySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SpeedElemNames = new ArrayList(); + SpeedElemNames.add("0"); + List SpeedEnumOptions = new ArrayList(); + SpeedEnumOptions.add("2400"); + SpeedEnumOptions.add("4800"); + SpeedEnumOptions.add("9600"); + SpeedEnumOptions.add("19200"); + SpeedEnumOptions.add("38400"); + SpeedEnumOptions.add("57600"); + SpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Speed").setValue(5); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TelemetrySettings obj = new TelemetrySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA608C526; + protected static final String NAME = "TelemetrySettings"; + protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java new file mode 100644 index 000000000..4eca6ea82 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -0,0 +1,87 @@ +/** + ****************************************************************************** + * + * + * @file uavobjectsinittemplate.java + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief the template for the uavobjects init part + * $(GENERATEDWARNING) + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.UAVObjectManager; + +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { + objMngr.registerObject( new ActuatorCommand() ); + objMngr.registerObject( new ActuatorDesired() ); + objMngr.registerObject( new ActuatorSettings() ); + objMngr.registerObject( new AHRSCalibration() ); + objMngr.registerObject( new AHRSSettings() ); + objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AttitudeActual() ); + objMngr.registerObject( new AttitudeRaw() ); + objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new BaroAltitude() ); + objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatteryState() ); + objMngr.registerObject( new FlightPlanControl() ); + objMngr.registerObject( new FlightPlanSettings() ); + objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSTelemetryStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GuidanceSettings() ); + objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new ManualControlCommand() ); + objMngr.registerObject( new ManualControlSettings() ); + objMngr.registerObject( new MixerSettings() ); + objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PositionActual() ); + objMngr.registerObject( new PositionDesired() ); + objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new SonarAltitude() ); + objMngr.registerObject( new StabilizationDesired() ); + objMngr.registerObject( new StabilizationSettings() ); + objMngr.registerObject( new SystemAlarms() ); + objMngr.registerObject( new SystemSettings() ); + objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TelemetrySettings() ); + objMngr.registerObject( new VelocityActual() ); + objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new WatchdogStatus() ); + + } catch (Exception e) { + e.printStackTrace(); + } + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java new file mode 100644 index 000000000..649e6c122 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + +generated from velocityactual.xml + **/ +public class VelocityActual extends UAVDataObject { + + public VelocityActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityActual obj = new VelocityActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityActual)(objMngr.getObject(VelocityActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x48009C88; + protected static final String NAME = "VelocityActual"; + protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java new file mode 100644 index 000000000..27f290898 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + +generated from velocitydesired.xml + **/ +public class VelocityDesired extends UAVDataObject { + + public VelocityDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityDesired obj = new VelocityDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityDesired)(objMngr.getObject(VelocityDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x122F5E3A; + protected static final String NAME = "VelocityDesired"; + protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java new file mode 100644 index 000000000..3adcad96b --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * For monitoring the flags in the watchdog and especially the bootup flags + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +For monitoring the flags in the watchdog and especially the bootup flags + +generated from watchdogstatus.xml + **/ +public class WatchdogStatus extends UAVDataObject { + + public WatchdogStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BootupFlagsElemNames = new ArrayList(); + BootupFlagsElemNames.add("0"); + fields.add( new UAVObjectField("BootupFlags", "", UAVObjectField.FieldType.UINT16, BootupFlagsElemNames, null) ); + + List ActiveFlagsElemNames = new ArrayList(); + ActiveFlagsElemNames.add("0"); + fields.add( new UAVObjectField("ActiveFlags", "", UAVObjectField.FieldType.UINT16, ActiveFlagsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WatchdogStatus obj = new WatchdogStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WatchdogStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (WatchdogStatus)(objMngr.getObject(WatchdogStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD646E910; + protected static final String NAME = "WatchdogStatus"; + protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From 72de0c622aa4116a3067cc6fa97e7638063221fb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:12:32 -0600 Subject: [PATCH 205/508] Removed various debugging outputs and exceptions for now (will add back in a more principled manner later). Also updated the auto generated code. --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 30 +++++++---- .../templates/uavobjectsinittemplate.java | 52 ++++--------------- .../templates/uavobjecttemplate.java | 6 +-- .../java/uavobjectgeneratorjava.cpp | 4 +- 7 files changed, 37 insertions(+), 63 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index b24a2abf5..6f3f456df 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,6 +1,7 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index f0a2248f5..de04f81c5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,7 +9,7 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); mobj = null; this.isSet = isSet; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index bf2c87d7e..cc6718ebd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -105,10 +105,9 @@ public abstract class UAVObject { * When unable to unpack a field */ public void initializeFields(List fields, ByteBuffer data, - int numBytes) throws Exception { + int numBytes) { // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; -// this.data = data; this.fields = fields; // Initialize fields for (int n = 0; n < fields.size(); ++n) { @@ -288,7 +287,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ebd7b52..a5fc6b7da 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,8 @@ public class UAVObjectField { * to the arm/uavtalk standard (little endian) * @param dataOut * @return the number of bytes added - * @throws Exception */ - public int pack(ByteBuffer dataOut) throws Exception { + **/ + public int pack(ByteBuffer dataOut) { //QMutexLocker locker(obj->getMutex()); // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); @@ -147,7 +147,7 @@ public class UAVObjectField { break; case STRING: // TODO: Implement strings - throw new Exception("Strings not yet implemented"); + throw new Error("Strings not yet implemented"); } // Done return getNumBytes(); @@ -358,13 +358,13 @@ public class UAVObjectField { } } - public double getDouble() throws Exception { return getDouble(0); }; - public double getDouble(int index) throws Exception { + public double getDouble() { return getDouble(0); }; + public double getDouble(int index) { return Double.valueOf((Double) getValue(index)); } - public void setDouble(double value) throws Exception { setDouble(value, 0); }; - public void setDouble(double value, int index) throws Exception { + public void setDouble(double value) { setDouble(value, 0); }; + public void setDouble(double value, int index) { setValue(value, index); } @@ -436,9 +436,7 @@ public class UAVObjectField { String sout = new String(); sout += name + ": [ "; for (int n = 0; n < numElements; ++n) - { sout += String.valueOf(n) + "(" + getValue(n) + ") "; - } sout += "] " + units + "\n"; return sout; @@ -488,6 +486,18 @@ public class UAVObjectField { ((ArrayList) data).add((long) 0); } break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -546,8 +556,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - - System.out.println(this); } /** diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java index 5185ab237..7f9edb791 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java @@ -26,50 +26,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -package org.openpilot.uavtalk; +package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.uavobjects.*; -import org.openpilot.uavtalk.UAVObject; -import java.util.HashMap; +import org.openpilot.uavtalk.UAVObjectManager; -public class UAVObjects { - - private static UAVObject[] uavobjects=null; - private static HashMap id2obj; - - public static void init() { - if (uavobjects==null) { - uavobjects=new UAVObject[] { -$(OBJINIT) - }; - id2obj=new HashMap(); - for (int i=0;i< uavobjects.length;i++) - id2obj.put(uavobjects[i].getObjID(),i); +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { +$(OBJINIT) + } catch (Exception e) { + e.printStackTrace(); + } } - } - - public static UAVObject[] getUAVObjectArray() { - return uavobjects; - } - - public static boolean hasObjectWithID(int id) { - return id2obj.containsKey(id); - } - - public static UAVObject getObjectByID(int id) { - if (!hasObjectWithID(id)) - return null; - return uavobjects[(Integer)id2obj.get(id)]; - } - - public static UAVObject getObjectByName(String name) { - return uavobjects[0]; - } - - public static void printAll() { - for (UAVObject obj : uavobjects) - System.out.println(obj.getObjName()); - } - -$(OBJGETTER) } \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index af8f48fce..64e2461f5 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -36,7 +36,6 @@ import java.util.ListIterator; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; import org.openpilot.uavtalk.UAVObjectField; /** @@ -46,7 +45,7 @@ generated from $(XMLFILE) **/ public class $(NAME) extends UAVDataObject { - public $(NAME)() throws Exception { + public $(NAME)() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); @@ -57,10 +56,9 @@ $(FIELDSINIT) int numBytes = 0; ListIterator li = fields.listIterator(); while(li.hasNext()) { - numBytes += li.next().getNumBytesElement(); + numBytes += li.next().getNumBytes(); } NUMBYTES = numBytes; - // Initialize object initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 7319b7767..b8d4b33d5 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -54,14 +54,14 @@ bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepa ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + javaObjInit.append("\t\t\tobjMngr.registerObject( new " + info->name + "() );\n"); objInc.append("#include \"" + info->namelc + ".h\"\n"); } // Write the gcs object inialization files javaInitTemplate.replace( QString("$(OBJINC)"), objInc); javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/UAVObjectsInitialize.java", javaInitTemplate ); if (!res) { cout << "Error: Could not write output files" << endl; return false; From 6758d5c5982c480c4301eee0e97b91477aecb30f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:33:56 -0600 Subject: [PATCH 206/508] Make the initial values for enums be the string. Make setValue accept numerical or string constants for enums. Only returns a string though. --- .../src/org/openpilot/uavtalk/UAVObjectField.java | 10 ++++++++-- .../generators/java/uavobjectgeneratorjava.cpp | 8 ++++---- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a5fc6b7da..bb525a5e0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -343,8 +343,14 @@ public class UAVObjectField { break; } case ENUM: - { - byte val = (byte) options.indexOf((String) data); + { + byte val; + try { + // Test if numeric constant passed in + val = ((Number) data).byteValue(); + } catch (Exception e) { + val = (byte) options.indexOf((String) data); + } //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index b8d4b33d5..e942b238f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -210,9 +210,9 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%2\");\n") .arg( info->fields[n]->name ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + .arg( info->fields[n]->defaultValues[0] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { @@ -233,10 +233,10 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) for (int idx = 0; idx < info->fields[n]->numElements; ++idx) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%3\",%2);\n") .arg( info->fields[n]->name ) .arg( idx ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + .arg( info->fields[n]->defaultValues[idx] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") From 3a71d26604dea12f4d6d5c9d3c00dcb3e7bd0416 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:36:49 -0600 Subject: [PATCH 207/508] Some cosmetic changes, also initialize the Metadata properly --- .../src/org/openpilot/uavtalk/UAVMetaObject.java | 13 ++++++++++++- androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObjectField.java | 6 +----- 3 files changed, 14 insertions(+), 7 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 70e661d46..98e4bd626 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -3,12 +3,15 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.ArrayList; import java.util.List; +import java.util.ListIterator; public class UAVMetaObject extends UAVObject { public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; + + ownMetadata = new Metadata(); ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; @@ -48,9 +51,17 @@ public class UAVMetaObject extends UAVObject { fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + + // Initialize object + // Initialize parent super.initialize(0); - super.initializeFields(fields, ByteBuffer.allocate(10), 10); + initializeFields(fields, ByteBuffer.allocate(numBytes), numBytes); // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index cc6718ebd..a990def2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -461,7 +461,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index bb525a5e0..0b72c33c8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -440,11 +440,7 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": [ "; - for (int n = 0; n < numElements; ++n) - sout += String.valueOf(n) + "(" + getValue(n) + ") "; - - sout += "] " + units + "\n"; + sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; return sout; } From 6158e19df15160ddffbfa61ef75172f4bbe2608a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:11 -0600 Subject: [PATCH 208/508] Initial implementation of UAVTalk protocol and a test platform for it and the UAVObjectManager --- .../openpilot/uavtalk/UAVObjectManager.java | 22 + .../src/org/openpilot/uavtalk/UAVTalk.java | 808 ++++++++++++++++++ .../org/openpilot/uavtalk/ObjMngrTest.java | 22 + .../tests/org/openpilot/uavtalk/TalkTest.java | 74 ++ 4 files changed, 926 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVTalk.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TalkTest.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index d75b14b85..2e531fc85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -118,6 +118,7 @@ public class UAVObjectManager { // Create metaobject String mname = obj.getName(); mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); // Initialize object obj.initialize(0, mobj); @@ -224,6 +225,17 @@ public class UAVObjectManager { */ } + + /** + * Returns a specific object by name only, returns instance ID zero + * @param name The object name + * @return The object or null if not found + */ + public UAVObject getObject(String name) + { + return getObject(name, 0, 0); + } + /** * Get a specific object given its name and instance ID * @returns The object is found or NULL if not @@ -233,6 +245,16 @@ public class UAVObjectManager { return getObject(name, 0, instId); } + /** + * Get a specific object with given object ID and instance ID zero + * @param objId the object id + * @returns The object is found or NULL if not + */ + public UAVObject getObject(int objId) + { + return getObject(null, objId, 0); + } + /** * Get a specific object given its object and instance ID * @returns The object is found or NULL if not diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java new file mode 100644 index 000000000..07b061bc9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -0,0 +1,808 @@ +package org.openpilot.uavtalk; + +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; +import java.io.IOException; +import java.io.InputStream; +import java.io.OutputStream; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; + +public class UAVTalk { + + /** + * Constants + */ + private static final int SYNC_VAL = 0x3C; + + private static final short crc_table[] = { + 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, + 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, + 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, + 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, + 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, + 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, + 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, + 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, + 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, + 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, + 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, + 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, + 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, + 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 + }; + + enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + + static final int TYPE_MASK = 0xFC; + static final int TYPE_VER = 0x20; + static final int TYPE_OBJ = (TYPE_VER | 0x00); + static final int TYPE_OBJ_REQ = (TYPE_VER | 0x01); + static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); + static final int TYPE_ACK = (TYPE_VER | 0x03); + + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + + static final int CHECKSUM_LENGTH = 1; + + static final int MAX_PAYLOAD_LENGTH = 256; + + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + + static final int ALL_INSTANCES = 0xFFFF; + static final int TX_BUFFER_SIZE = 2*1024; + + /** + * Private data + */ + InputStream inStream; + OutputStream outStream; + UAVObjectManager objMngr; + + UAVObject respObj; + boolean respAllInstances; + // Variables used by the receive state machine + ByteBuffer rxTmpBuffer /* 4 */; + ByteBuffer rxBuffer; + int rxType; + int rxObjId; + int rxInstId; + int rxLength; + int rxPacketLength; + + int rxCSPacket, rxCS; + int rxCount; + int packetSize; + RxStateType rxState; + ComStats stats = new ComStats(); + + /** + * Comm stats + */ + public class ComStats { + public int txBytes = 0; + public int rxBytes = 0; + public int txObjectBytes = 0; + public int rxObjectBytes = 0; + public int rxObjects = 0; + public int txObjects = 0; + public int txErrors = 0; + public int rxErrors = 0; + } + + /** + * Constructor + */ + public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) + { + this.objMngr = objMngr; + this.inStream = inStream; + this.outStream = outStream; + + rxState = RxStateType.STATE_SYNC; + rxPacketLength = 0; + + //mutex = new QMutex(QMutex::Recursive); + + respObj = null; + resetStats(); + rxTmpBuffer = ByteBuffer.allocate(4); + rxTmpBuffer.order(ByteOrder.LITTLE_ENDIAN); + rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); + rxBuffer.order(ByteOrder.LITTLE_ENDIAN); + + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + } + + /** + * Reset the statistics counters + */ + public void resetStats() + { + //QMutexLocker locker(mutex); + stats = new ComStats(); + } + + /** + * Get the statistics counters + */ + public ComStats getStats() + { + //QMutexLocker locker(mutex); + return stats; + } + + /** + * Called each time there are data in the input buffer + */ + public void processInputStream() + { + int val; + + while (true) + { + try { + //inStream.wait(); + val = inStream.read(); + } /*catch (InterruptedException e) { + // TODO Auto-generated catch block + System.out.println("Connection was aborted\n"); + e.printStackTrace(); + break; + }*/ catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + break; + } + //System.out.println("Received byte " + val + " in state + " + rxState); + processInputByte(val); + } + } + + /** + * Request an update for the specified object, on success the object data would have been + * updated by the GCS. + * \param[in] obj Object to update + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) + { + //QMutexLocker locker(mutex); + return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); + } + + /** + * Send the specified object through the telemetry link. + * \param[in] obj Object to send + * \param[in] acked Selects if an ack is required + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + { + //QMutexLocker locker(mutex); + if (acked) + { + return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); + } + else + { + return objectTransaction(obj, TYPE_OBJ, allInstances); + } + } + + /** + * Cancel a pending transaction + */ + public void cancelTransaction() + { + //QMutexLocker locker(mutex); + respObj = null; + } + + /** + * Execute the requested transaction on an object. + * \param[in] obj Object + * \param[in] type Transaction type + * TYPE_OBJ: send object, + * TYPE_OBJ_REQ: request object update + * TYPE_OBJ_ACK: send object with an ack + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) + { + // Send object depending on if a response is needed + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) + { + if ( transmitObject(obj, type, allInstances) ) + { + respObj = obj; + respAllInstances = allInstances; + return true; + } + else + { + return false; + } + } + else if (type == TYPE_OBJ) + { + return transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + return false; + } + } + + /** + * Process an byte from the telemetry stream. + * \param[in] rxbyte Received byte + * \return Success (true), Failure (false) + */ + public boolean processInputByte(int rxbyte) + { + assert(objMngr != null); + + // Update stats + stats.rxBytes++; + + rxPacketLength++; // update packet byte count + + // Receive state machine + switch (rxState) + { + case STATE_SYNC: + + if (rxbyte != SYNC_VAL) + break; + + // Initialize and update CRC + rxCS = updateCRC(0, rxbyte); + + rxPacketLength = 1; + + rxState = RxStateType.STATE_TYPE; + break; + + case STATE_TYPE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if ((rxbyte & TYPE_MASK) != TYPE_VER) + { + rxState = RxStateType.STATE_SYNC; + break; + } + + rxType = rxbyte; + + packetSize = 0; + + rxState = RxStateType.STATE_SIZE; + rxCount = 0; + break; + + case STATE_SIZE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if (rxCount == 0) + { + packetSize += rxbyte; + rxCount++; + break; + } + + packetSize += (rxbyte << 8) & 0xff00; + + if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) + { // incorrect packet size + rxState = RxStateType.STATE_SYNC; + break; + } + + rxCount = 0; + rxState = RxStateType.STATE_OBJID; + rxTmpBuffer.position(0); + break; + + case STATE_OBJID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 4) + break; + + // Search for object, if not found reset state machine + rxObjId = rxTmpBuffer.getInt(0); + { + UAVObject rxObj = objMngr.getObject(rxObjId); + if (rxObj == null) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Determine data length + if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK) + rxLength = 0; + else + rxLength = rxObj.getNumBytes(); + + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check if this is a single instance object (i.e. if the instance ID field is coming next) + if (rxObj.isSingleInstance()) + { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } + else + { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } + } + + break; + + case STATE_INSTID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 2) + break; + + rxInstId = rxTmpBuffer.getShort(0); + + rxCount = 0; + + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + + break; + + case STATE_DATA: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + //System.out.println(rxCount + "/" + rxLength); + rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < rxLength) + break; + + rxState = RxStateType.STATE_CS; + rxCount = 0; + break; + + case STATE_CS: + + // The CRC byte + rxCSPacket = rxbyte; + + if (rxCS != rxCSPacket) + { // packet error - faulty CRC + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + if (rxPacketLength != (packetSize + 1)) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + //mutex->lock(); + rxBuffer.position(0); + receiveObject(rxType, rxObjId, rxInstId, rxBuffer); + stats.rxObjectBytes += rxLength; + stats.rxObjects++; + //mutex->unlock(); + + rxState = RxStateType.STATE_SYNC; + break; + + default: + rxState = RxStateType.STATE_SYNC; + stats.rxErrors++; + } + + // Done + return true; + } + + /** + * Receive an object. This function process objects received through the telemetry stream. + * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) + * \param[in] obj Handle of the received object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] data Data buffer + * \param[in] length Buffer length + * \return Success (true), Failure (false) + */ + public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + UAVObject obj = null; + boolean error = false; + boolean allInstances = (instId == ALL_INSTANCES? true : false); + + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + // Process message type + switch (type) { + case TYPE_OBJ: + // All instances, not allowed for OBJ messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Check if an ack is pending + if ( obj != null ) + { + updateAck(obj); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_ACK: + // All instances, not allowed for OBJ_ACK messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Transmit ACK + if ( obj != null ) + { + transmitObject(obj, TYPE_ACK, false); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_REQ: + // Get object, if all instances are requested get instance 0 of the object + if (allInstances) + { + obj = objMngr.getObject(objId); + } + else + { + obj = objMngr.getObject(objId, instId); + } + // If object was found transmit it + if (obj != null) + { + transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + error = true; + } + break; + case TYPE_ACK: + // All instances, not allowed for ACK messages + if (!allInstances) + { + // Get object + obj = objMngr.getObject(objId, instId); + // Check if an ack is pending + if (obj != null) + { + updateAck(obj); + } + else + { + error = true; + } + } + break; + default: + error = true; + } + // Done + return !error; + } + + /** + * Update the data of an object from a byte array (unpack). + * If the object instance could not be found in the list, then a + * new one is created. + */ + public UAVObject updateObject(int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + // Get object + UAVObject obj = objMngr.getObject(objId, instId); + // If the instance does not exist create it + if (obj == null) + { + // Get the object type + UAVObject tobj = objMngr.getObject(objId); + if (tobj == null) + { + return null; + } + // Make sure this is a data object + UAVDataObject dobj = null; + try { + dobj = (UAVDataObject) tobj; + } catch (Exception e) { + // Failed to cast to a data object + return null; + } + + // Create a new instance, unpack and register + UAVDataObject instobj = dobj.clone(instId); + try { + if ( !objMngr.registerObject(instobj) ) + { + return null; + } + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + instobj.unpack(data); + return instobj; + } + else + { + // Unpack data into object instance + // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + obj.unpack(data); + return obj; + } + } + + /** + * Check if a transaction is pending and if yes complete it. + */ + public void updateAck(UAVObject obj) + { + if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) + { + respObj = null; + // TODO: Signals +// emit transactionCompleted(obj); + } + } + + /** + * Send an object through the telemetry link. + * \param[in] obj Object to send + * \param[in] type Transaction type + * \param[in] allInstances True is all instances of the object are to be sent + * \return Success (true), Failure (false) + */ + public boolean transmitObject(UAVObject obj, int type, boolean allInstances) + { + // If all instances are requested on a single instance object it is an error + if (allInstances && obj.isSingleInstance()) + { + allInstances = false; + } + + // Process message type + if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) + { + if (allInstances) + { + // Get number of instances + int numInst = objMngr.getNumInstances(obj.getObjID()); + // Send all instances + for (int instId = 0; instId < numInst; ++instId) + { + UAVObject inst = objMngr.getObject(obj.getObjID(), instId); + transmitSingleObject(inst, type, false); + } + return true; + } + else + { + return transmitSingleObject(obj, type, false); + } + } + else if (type == TYPE_OBJ_REQ) + { + return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); + } + else if (type == TYPE_ACK) + { + if (!allInstances) + { + return transmitSingleObject(obj, TYPE_ACK, false); + } + else + { + return false; + } + } + else + { + return false; + } + } + + + /** + * Send an object through the telemetry link. + * \param[in] obj Object handle to send + * \param[in] type Transaction type + * \return Success (true), Failure (false) + */ + public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + { + int length; + int dataOffset; + int objId; + int instId; + int allInstId = ALL_INSTANCES; + + assert(objMngr != null && outStream != null); + + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); + bbuf.order(ByteOrder.LITTLE_ENDIAN); + + // Determine data length + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) + { + length = 0; + } + else + { + length = obj.getNumBytes(); + } + + // Setup type and object id fields + bbuf.put((byte) (SYNC_VAL & 0xff)); + bbuf.put((byte) (type & 0xff)); + bbuf.putShort((short) (length + + 2 /* SYNC, Type */ + + 2 /* Size */ + + 4 /* ObjID */ + + (obj.isSingleInstance() ? 0 : 2) )); + bbuf.putInt(obj.getObjID()); + + // Setup instance ID if one is required + if ( !obj.isSingleInstance() ) + { + // Check if all instances are requested + if (allInstances) + bbuf.putShort((short) (allInstId & 0xffff)); + else + bbuf.putShort((short) (obj.getInstID() & 0xffff)); + } + + // Check length + if (length >= MAX_PAYLOAD_LENGTH) + return false; + + // Copy data (if any) + if (length > 0) + try { + if ( obj.pack(bbuf) == 0) + return false; + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + + // Calculate checksum + bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + + try { + outStream.write(bbuf.array()); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + +// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE +// // Send buffer, check that the transmit backlog does not grow above limit +// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) +// { +// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); +// } +// else +// { +// ++stats.txErrors; +// return false; +// } + + // Update stats + ++stats.txObjects; + stats.txBytes += bbuf.position(); + stats.txObjectBytes += length; + + // Done + return true; + } + + /** + * Update the crc value with new data. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ + * using the configuration: + * Width = 8 + * Poly = 0x07 + * XorIn = 0x00 + * ReflectIn = False + * XorOut = 0x00 + * ReflectOut = False + * Algorithm = table-driven + * + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param length Number of bytes in the \a data buffer. + * \return The updated crc value. + */ + int updateCRC(int crc, int data) + { + return crc_table[crc ^ (data & 0xff)]; + } + int updateCRC(int crc, byte [] data) + { + for (int i = 0; i < data.length; i++) + crc = updateCRC(crc, (int) data[i]); + return crc; + } + + + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java new file mode 100644 index 000000000..0131d1246 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java @@ -0,0 +1,22 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjMngrTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetObjects() { + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); +// System.out.println(objMngr.getObject("ActuatorSettings", 0)); + } + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java new file mode 100644 index 000000000..6dc23530e --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -0,0 +1,74 @@ +package org.openpilot.uavtalk; +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TalkTest { + + static UAVObjectManager objMngr; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 8000; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + @Test + public void testProcessInputStream() { + Socket connection = null; + UAVTalk talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + talk.processInputStream(); + } + + @Test + public void testSendObjectRequest() { + fail("Not yet implemented"); + } + + @Test + public void testSendObject() { + fail("Not yet implemented"); + } + + @Test + public void testReceiveObject() { + fail("Not yet implemented"); + } + + @Test + public void testUpdateObject() { + fail("Not yet implemented"); + } + +} From c7f57dffe3b147698a2057401a2de166bfca8bbf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:39 -0600 Subject: [PATCH 209/508] Updates to various objects --- .../uavtalk/uavobjects/AHRSCalibration.java | 2 +- .../uavtalk/uavobjects/AHRSSettings.java | 4 +- .../uavtalk/uavobjects/ActuatorSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/BatterySettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 4 +- .../uavtalk/uavobjects/HomeLocation.java | 2 +- .../uavobjects/ManualControlSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/MixerSettings.java | 16 +++---- .../uavtalk/uavobjects/SystemAlarms.java | 32 +++++++------- .../uavtalk/uavobjects/SystemSettings.java | 2 +- .../uavtalk/uavobjects/TelemetrySettings.java | 2 +- 13 files changed, 80 insertions(+), 80 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index a3096ad39..922582398 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -171,7 +171,7 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue(0); + getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index a38915c28..c49c04778 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -132,10 +132,10 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Algorithm").setValue(1); + getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); getField("YawBias").setValue(0); getField("PitchBias").setValue(0); getField("RollBias").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index ebbfaeb17..542b433d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -358,20 +358,20 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue(8); - getField("FixedWingRoll2").setValue(8); - getField("FixedWingPitch1").setValue(8); - getField("FixedWingPitch2").setValue(8); - getField("FixedWingYaw").setValue(8); - getField("FixedWingThrottle").setValue(8); - getField("VTOLMotorN").setValue(8); - getField("VTOLMotorNE").setValue(8); - getField("VTOLMotorE").setValue(8); - getField("VTOLMotorSE").setValue(8); - getField("VTOLMotorS").setValue(8); - getField("VTOLMotorSW").setValue(8); - getField("VTOLMotorW").setValue(8); - getField("VTOLMotorNW").setValue(8); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -400,14 +400,14 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); - getField("ChannelType").setValue(0,0); - getField("ChannelType").setValue(0,1); - getField("ChannelType").setValue(0,2); - getField("ChannelType").setValue(0,3); - getField("ChannelType").setValue(0,4); - getField("ChannelType").setValue(0,5); - getField("ChannelType").setValue(0,6); - getField("ChannelType").setValue(0,7); + getField("ChannelType").setValue("PWM",0); + getField("ChannelType").setValue("PWM",1); + getField("ChannelType").setValue("PWM",2); + getField("ChannelType").setValue("PWM",3); + getField("ChannelType").setValue("PWM",4); + getField("ChannelType").setValue("PWM",5); + getField("ChannelType").setValue("PWM",6); + getField("ChannelType").setValue("PWM",7); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java index 19e477b62..6af673930 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -121,7 +121,7 @@ public class BatterySettings extends UAVDataObject { { getField("BatteryVoltage").setValue(11.1); getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue(0); + getField("BatteryType").setValue("LiPo"); getField("Calibrations").setValue(1,0); getField("Calibrations").setValue(1,1); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index 2e453eda5..fdc5bfcb0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -104,7 +104,7 @@ public class FlightPlanControl extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Command").setValue(0); + getField("Command").setValue("Start"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 00920553c..2303514c0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -144,8 +144,8 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Status").setValue(0); - getField("ErrorType").setValue(0); + getField("Status").setValue("Stopped"); + getField("ErrorType").setValue("None"); getField("Debug1").setValue(0); getField("Debug2").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2cde12f64..2fe8bb437 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -142,7 +142,7 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue(0); + getField("GuidanceMode").setValue("DUAL_LOOP"); getField("HorizontalP").setValue(0.2,0); getField("HorizontalP").setValue(150,1); getField("HorizontalVelPID").setValue(0.1,0); @@ -155,7 +155,7 @@ public class GuidanceSettings extends UAVDataObject { getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue(0); + getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 2adebce70..5941c069c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -139,7 +139,7 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue(0); + getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c14aef758..83697999a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -309,28 +309,28 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue(0); - getField("Roll").setValue(0); - getField("Pitch").setValue(1); - getField("Yaw").setValue(2); - getField("Throttle").setValue(3); - getField("FlightMode").setValue(4); - getField("Accessory1").setValue(8); - getField("Accessory2").setValue(8); - getField("Accessory3").setValue(8); - getField("Arming").setValue(0); - getField("Stabilization1Settings").setValue(2,0); - getField("Stabilization1Settings").setValue(2,1); - getField("Stabilization1Settings").setValue(2,2); - getField("Stabilization2Settings").setValue(2,0); - getField("Stabilization2Settings").setValue(2,1); - getField("Stabilization2Settings").setValue(2,2); - getField("Stabilization3Settings").setValue(2,0); - getField("Stabilization3Settings").setValue(2,1); - getField("Stabilization3Settings").setValue(2,2); - getField("FlightModePosition").setValue(0,0); - getField("FlightModePosition").setValue(1,1); - getField("FlightModePosition").setValue(2,2); + getField("InputMode").setValue("PWM"); + getField("Roll").setValue("Channel1"); + getField("Pitch").setValue("Channel2"); + getField("Yaw").setValue("Channel3"); + getField("Throttle").setValue("Channel4"); + getField("FlightMode").setValue("Channel5"); + getField("Accessory1").setValue("None"); + getField("Accessory2").setValue("None"); + getField("Accessory3").setValue("None"); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Attitude",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Attitude",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Attitude",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Manual",1); + getField("FlightModePosition").setValue("Manual",2); getField("ChannelMax").setValue(2000,0); getField("ChannelMax").setValue(2000,1); getField("ChannelMax").setValue(2000,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 554e366f3..9aa87d49e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -270,49 +270,49 @@ public class MixerSettings extends UAVDataObject { getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); - getField("Mixer1Type").setValue(0); + getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); getField("Mixer1Vector").setValue(0,2); getField("Mixer1Vector").setValue(0,3); getField("Mixer1Vector").setValue(0,4); - getField("Mixer2Type").setValue(0); + getField("Mixer2Type").setValue("Disabled"); getField("Mixer2Vector").setValue(0,0); getField("Mixer2Vector").setValue(0,1); getField("Mixer2Vector").setValue(0,2); getField("Mixer2Vector").setValue(0,3); getField("Mixer2Vector").setValue(0,4); - getField("Mixer3Type").setValue(0); + getField("Mixer3Type").setValue("Disabled"); getField("Mixer3Vector").setValue(0,0); getField("Mixer3Vector").setValue(0,1); getField("Mixer3Vector").setValue(0,2); getField("Mixer3Vector").setValue(0,3); getField("Mixer3Vector").setValue(0,4); - getField("Mixer4Type").setValue(0); + getField("Mixer4Type").setValue("Disabled"); getField("Mixer4Vector").setValue(0,0); getField("Mixer4Vector").setValue(0,1); getField("Mixer4Vector").setValue(0,2); getField("Mixer4Vector").setValue(0,3); getField("Mixer4Vector").setValue(0,4); - getField("Mixer5Type").setValue(0); + getField("Mixer5Type").setValue("Disabled"); getField("Mixer5Vector").setValue(0,0); getField("Mixer5Vector").setValue(0,1); getField("Mixer5Vector").setValue(0,2); getField("Mixer5Vector").setValue(0,3); getField("Mixer5Vector").setValue(0,4); - getField("Mixer6Type").setValue(0); + getField("Mixer6Type").setValue("Disabled"); getField("Mixer6Vector").setValue(0,0); getField("Mixer6Vector").setValue(0,1); getField("Mixer6Vector").setValue(0,2); getField("Mixer6Vector").setValue(0,3); getField("Mixer6Vector").setValue(0,4); - getField("Mixer7Type").setValue(0); + getField("Mixer7Type").setValue("Disabled"); getField("Mixer7Vector").setValue(0,0); getField("Mixer7Vector").setValue(0,1); getField("Mixer7Vector").setValue(0,2); getField("Mixer7Vector").setValue(0,3); getField("Mixer7Vector").setValue(0,4); - getField("Mixer8Type").setValue(0); + getField("Mixer8Type").setValue("Disabled"); getField("Mixer8Vector").setValue(0,0); getField("Mixer8Vector").setValue(0,1); getField("Mixer8Vector").setValue(0,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 9136627f4..e9313472c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -121,22 +121,22 @@ public class SystemAlarms extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Alarm").setValue(0,0); - getField("Alarm").setValue(0,1); - getField("Alarm").setValue(0,2); - getField("Alarm").setValue(0,3); - getField("Alarm").setValue(0,4); - getField("Alarm").setValue(0,5); - getField("Alarm").setValue(0,6); - getField("Alarm").setValue(0,7); - getField("Alarm").setValue(0,8); - getField("Alarm").setValue(0,9); - getField("Alarm").setValue(0,10); - getField("Alarm").setValue(0,11); - getField("Alarm").setValue(0,12); - getField("Alarm").setValue(0,13); - getField("Alarm").setValue(0,14); - getField("Alarm").setValue(0,15); + getField("Alarm").setValue("Uninitialised",0); + getField("Alarm").setValue("Uninitialised",1); + getField("Alarm").setValue("Uninitialised",2); + getField("Alarm").setValue("Uninitialised",3); + getField("Alarm").setValue("Uninitialised",4); + getField("Alarm").setValue("Uninitialised",5); + getField("Alarm").setValue("Uninitialised",6); + getField("Alarm").setValue("Uninitialised",7); + getField("Alarm").setValue("Uninitialised",8); + getField("Alarm").setValue("Uninitialised",9); + getField("Alarm").setValue("Uninitialised",10); + getField("Alarm").setValue("Uninitialised",11); + getField("Alarm").setValue("Uninitialised",12); + getField("Alarm").setValue("Uninitialised",13); + getField("Alarm").setValue("Uninitialised",14); + getField("Alarm").setValue("Uninitialised",15); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index d01b55b24..99bceb6ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -117,7 +117,7 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("AirframeType").setValue(0); + getField("AirframeType").setValue("FixedWing"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java index 6995a02b0..675f9b592 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -108,7 +108,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue(5); + getField("Speed").setValue("57600"); } From 97b5f758a01e1e5e925abbaad1ba8b6b710ad146 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:54:43 -0600 Subject: [PATCH 210/508] Made a lot of critical functions synchronized to block race conditions (essentialy implements a mutex locker for that object). Also added callbacks to UAVObjects for unpacked and updated. More to come. Finally test case that checks that we get FlightStatus through UAVTalk (i.e. that the aircraft is talking). --- .../src/org/openpilot/uavtalk/UAVObject.java | 49 +++++++++++++++++-- .../org/openpilot/uavtalk/UAVObjectField.java | 18 +++---- .../openpilot/uavtalk/UAVObjectManager.java | 14 +++--- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 ++++++- .../tests/org/openpilot/uavtalk/TalkTest.java | 33 +++++++++++-- 5 files changed, 107 insertions(+), 25 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index a990def2c..6ede86094 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -3,9 +3,50 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.List; import java.util.ListIterator; +import java.util.Observer; +import java.util.Observable; public abstract class UAVObject { + public class CallbackListener extends Observable { + private UAVObject parent; + + public CallbackListener(UAVObject parent) { + this.parent = parent; + } + + public void event () { + setChanged(); + notifyObservers(parent); + } + } + + private CallbackListener updatedListeners = new CallbackListener(this); + public void addUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.addObserver(o); + } + } + void updated() { + synchronized(updatedListeners) { + updatedListeners.event(); + } + } + + private CallbackListener unpackedListeners = new CallbackListener(this); + public void addUnpackedObserver(Observer o) { + synchronized(unpackedListeners) { + unpackedListeners.addObserver(o); + } + } + void unpacked() { + synchronized(unpackedListeners) { + System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); + unpackedListeners.event(); + } + } + + /** * Object update mode */ @@ -298,10 +339,12 @@ public abstract class UAVObject { UAVObjectField field = li.next(); numBytes += field.unpack(dataIn); } + + // Trigger all the listeners for the unpack event + unpacked(); + updated(); + return numBytes; - // TODO: Callbacks - // emit objectUnpacked(this); // trigger object updated event - // emit objectUpdated(this); } // /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 0b72c33c8..21444a04b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -91,8 +91,7 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public int pack(ByteBuffer dataOut) { - //QMutexLocker locker(obj->getMutex()); + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -153,7 +152,7 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -240,10 +239,9 @@ public class UAVObjectField { return getNumBytes(); } - Object getValue() { return getValue(0); }; + public Object getValue() { return getValue(0); }; @SuppressWarnings("unchecked") - Object getValue(int index) { -// QMutexLocker locker(obj->getMutex()); + public synchronized Object getValue(int index) { // Check that index is not out of bounds if ( index >= numElements ) { @@ -287,8 +285,7 @@ public class UAVObjectField { public void setValue(Object data) { setValue(data,0); } @SuppressWarnings("unchecked") - public void setValue(Object data, int index) { - // QMutexLocker locker(obj->getMutex()); + public synchronized void setValue(Object data, int index) { // Check that index is not out of bounds //if ( index >= numElements ); //throw new Exception("Index out of bounds"); @@ -361,6 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } + obj.updated(); } } @@ -449,7 +447,7 @@ public class UAVObjectField { } @SuppressWarnings("unchecked") - public void clear() { + public synchronized void clear() { switch (type) { case INT8: @@ -503,7 +501,7 @@ public class UAVObjectField { } } - public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + public synchronized void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { // Copy params this.name = name; this.units = units; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 2e531fc85..74ddb95fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -23,7 +23,7 @@ public class UAVObjectManager { * updates. * @throws Exception */ - public boolean registerObject(UAVDataObject obj) throws Exception + public synchronized boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -128,7 +128,7 @@ public class UAVObjectManager { return true; } - public void addObject(UAVObject obj) + public synchronized void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -143,15 +143,15 @@ public class UAVObjectManager { */ public List> getObjects() { - //QMutexLocker locker(mutex); return objects; } /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public List< List > getDataObjects() { + assert(false); // TOOD This return new ArrayList>(); /* QMutexLocker locker(mutex); @@ -190,6 +190,7 @@ public class UAVObjectManager { */ public List > getMetaObjects() { + assert(false); // TODO return new ArrayList< List >(); /* QMutexLocker locker(mutex); @@ -267,7 +268,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - public UAVObject getObject(String name, int objId, int instId) + public synchronized UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -310,9 +311,8 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - public List getObjectInstances(String name, int objId) + public synchronized List getObjectInstances(String name, int objId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 07b061bc9..7ea9c7c60 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -10,6 +10,22 @@ import java.nio.ByteOrder; public class UAVTalk { + private Thread inputProcessingThread = null; + /** + * A reference to the thread for processing the incoming stream + * @return + */ + public Thread getInputProcessThread() { + if(inputProcessingThread == null) + + inputProcessingThread = new Thread() { + public void run() { + processInputStream(); + } + }; + return inputProcessingThread; + } + /** * Constants */ @@ -684,7 +700,7 @@ public class UAVTalk { * \param[in] type Transaction type * \return Success (true), Failure (false) */ - public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; int dataOffset; diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 6dc23530e..252927122 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -9,6 +9,8 @@ import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; import org.junit.BeforeClass; import org.junit.Test; @@ -20,8 +22,9 @@ public class TalkTest { static UAVObjectManager objMngr; static final String IP_ADDRDESS = new String("127.0.0.1"); - static final int PORT_NUM = 8000; - + static final int PORT_NUM = 7777; + boolean succeed = false; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -29,7 +32,7 @@ public class TalkTest { } @Test - public void testProcessInputStream() { + public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; try{ @@ -48,7 +51,29 @@ public class TalkTest { fail("Couldn't construct UAVTalk object"); } - talk.processInputStream(); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + succeed = false; + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + + obj.addUpdatedObserver( new Observer() { + public void update(Observable observable, Object data) { + // TODO Auto-generated method stub + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + try { + Thread.sleep(1000); + } catch (InterruptedException e1) { + } + + if(!succeed) + fail("Never received a FlightTelemetryStats update"); + } @Test From 1ffe0691f55820490c5178424b602eb7b017bf0f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:56:14 -0600 Subject: [PATCH 211/508] Test case for the callbacks --- .../org/openpilot/uavtalk/DataObjectTest.java | 95 +++++++++++++++++++ 1 file changed, 95 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java new file mode 100644 index 000000000..0f8106cc5 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java @@ -0,0 +1,95 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.ActuatorCommand; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.database.Observable; + +public class DataObjectTest { + + boolean succeed = false; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testUpdatedObserver() { + + succeed = false; + + UAVObject obj = new ActuatorCommand(); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + obj.updated(); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + @Test + public void testUpdatedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + objMngr.getObject("FlightTelemetryStats").updated(); + + if(!succeed) + fail("No callback"); + System.out.println("Done"); + + } + + @Test + public void testUnpackedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUnpackedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + ByteBuffer bbuf = ByteBuffer.allocate(obj.getNumBytes()); + objMngr.getObject("FlightTelemetryStats").unpack(bbuf); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + +} From 01e9d1a47231f7323250e25cb6edbe242c9dc5e0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:26:50 -0600 Subject: [PATCH 212/508] Add isMetadata() instead of testing whether dynamic cast fails --- androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java | 1 + androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 5 +++++ androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 1 + 3 files changed, 7 insertions(+) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index de04f81c5..5694cc9d8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,6 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } + public boolean isMetadata() { return true; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 98e4bd626..7aab176ef 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -66,6 +66,11 @@ public class UAVMetaObject extends UAVObject { // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); } + + @Override + public boolean isMetadata() { + return true; + }; /** * Get the parent object diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6ede86094..6d35df822 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -46,6 +46,7 @@ public abstract class UAVObject { } } + public abstract boolean isMetadata(); /** * Object update mode From b0f826758809c8d526d5a8f2f8ab7c8e4a05ef54 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:27:21 -0600 Subject: [PATCH 213/508] Initial start of the telemetry system which interfaces between UAVTalk and the ObjectManager/Objects --- .../src/org/openpilot/uavtalk/Telemetry.java | 25 ++ .../openpilot/uavtalk/TelemetryManager.java | 5 + .../openpilot/uavtalk/TelemetryMonitor.java | 263 ++++++++++++++++++ 3 files changed, 293 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/Telemetry.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java new file mode 100644 index 000000000..88bc33de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -0,0 +1,25 @@ +package org.openpilot.uavtalk; + +public class Telemetry { + + private TelemetryStats stats; + public class TelemetryStats { + public int txBytes; + public int rxBytes; + public int txObjectBytes; + public int rxObjectBytes; + public int rxObjects; + public int txObjects; + public int txErrors; + public int rxErrors; + public int txRetries; + } ; + + public TelemetryStats getStats() { + return stats; + } + + public void resetStats() { + stats = new TelemetryStats(); + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java new file mode 100644 index 000000000..7540a1423 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java @@ -0,0 +1,5 @@ +package org.openpilot.uavtalk; + +public class TelemetryManager { + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java new file mode 100644 index 000000000..40fc220cc --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -0,0 +1,263 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; +import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; + +import android.util.Log; + +public class TelemetryMonitor { + + private static final String TAG = "TelemetryMonitor"; + + static final int STATS_UPDATE_PERIOD_MS = 4000; + static final int STATS_CONNECT_PERIOD_MS = 1000; + static final int CONNECTION_TIMEOUT_MS = 8000; + + private UAVObjectManager objMngr; + private Telemetry tel; + private UAVObject objPending; + private UAVObject gcsStatsObj; + private UAVObject flightStatsObj; + private Timer periodicTask; + private int currentPeriod; + private List queue; + + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) + { + this.objMngr = objMngr; + this.tel = tel; + this.objPending = null; + queue = new ArrayList(); + + // Get stats objects + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + flightStatsObj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + flightStatsUpdated((UAVObject) data); + } + }); + + // Start update timer + setPeriod(STATS_CONNECT_PERIOD_MS); + } + + /** + * Initiate object retrieval, initialize queue with objects to be retrieved. + */ + public void startRetrievingObjects() + { + // Clear object queue + queue.clear(); + // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue + List< List > objs = objMngr.getObjects(); + + ListIterator> objListIterator = objs.listIterator(); + while( objListIterator.hasNext() ) + { + List instList = objListIterator.next(); + UAVObject obj = instList.get(0); + UAVObject.Metadata mdata = obj.getMetadata(); + if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + if ( obj.isMetadata() ) + { + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } + } + } + } + // Start retrieving + Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + retrieveNextObject(); + } + + /** + * Cancel the object retrieval + */ + public void stopRetrievingObjects() + { + //qxtLog->debug("Object retrieval has been cancelled"); + queue.clear(); + } + + /** + * Retrieve the next object in the queue + */ + public void retrieveNextObject() + { + // If queue is empty return + if ( queue.isEmpty() ) + { + //qxtLog->debug("Object retrieval completed"); + //emit connected(); + return; + } + // Get next object from the queue + UAVObject obj = queue.remove(0); + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; + // Connect to object + //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + // Request update + obj.requestUpdate(); + objPending = obj; + } + + /** + * Called by the retrieved object when a transaction is completed. + */ + public void transactionCompleted(UAVObject obj, boolean success) + { + //QMutexLocker locker(mutex); + // Disconnect from sending object + //obj->disconnect(this); + objPending = null; + + // Process next object if telemetry is still available + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + retrieveNextObject(); + } + else + { + stopRetrievingObjects(); + } + } + + /** + * Called each time the flight stats object is updated by the autopilot + */ + public synchronized void flightStatsUpdated(UAVObject obj) + { + // Force update if not yet connected + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + processStatsUpdates(); + } + } + + /** + * Called periodically to update the statistics and connection status. + */ + public synchronized void processStatsUpdates() + { + // Get telemetry stats + Telemetry.TelemetryStats telStats = tel.getStats(); + tel.resetStats(); + + // Update stats object + gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); + gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); + UAVObjectField field = gcsStatsObj.getField("RxFailures"); + field.setDouble(field.getDouble() + telStats.rxErrors); + field = gcsStatsObj.getField("TxFailures"); + field.setDouble(field.getDouble() + telStats.txErrors); + field = gcsStatsObj.getField("TxRetries"); + field.setDouble(field.getDouble() + telStats.txRetries); + + // Check for a connection timeout + boolean connectionTimeout; + if ( telStats.rxObjects > 0 ) + { + //connectionTimer.start(); + } + if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + { + connectionTimeout = true; + } + else + { + connectionTimeout = false; + } + + // Update connection state + int oldStatus = gcsStats.Status; + if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + { + // Request connection + gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + { + // Check for connection acknowledge + if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + { + gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + } + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + { + // Check if the connection is still active and the the autopilot is still connected + if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + { + gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + } + } + + // Set data + gcsStatsObj->setData(gcsStats); + + // Force telemetry update if not yet connected + if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || + flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + { + gcsStatsObj->updated(); + } + + // Act on new connections or disconnections + if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_UPDATE_PERIOD_MS); + statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot established"); + startRetrievingObjects(); + } + if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_CONNECT_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot lost"); + Log.d(TAG,"Trying to connect to the autopilot"); + emit disconnected(); + } + } + + private void setPeriod(int ms) { + if(periodicTask == null) + periodicTask = new Timer(); + + periodicTask.cancel(); + currentPeriod = ms; + periodicTask.scheduleAtFixedRate(new TimerTask() { + @Override + public void run() { + processStatsUpdates(); + } + }, currentPeriod, currentPeriod); + } + +} From 3d7f4e227304c1012a3e94305780f3cf00340a30 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 9 Mar 2011 02:44:25 -0600 Subject: [PATCH 214/508] A few more synchronized statements and deep cloning of objects --- .../src/org/openpilot/uavtalk/UAVObject.java | 30 ++-- .../org/openpilot/uavtalk/UAVObjectField.java | 13 +- .../openpilot/uavtalk/UAVObjectManager.java | 130 +++++++++--------- 3 files changed, 97 insertions(+), 76 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6d35df822..adfece03e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,6 +1,7 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; +import java.util.ArrayList; import java.util.List; import java.util.ListIterator; import java.util.Observer; @@ -128,8 +129,7 @@ public abstract class UAVObject { // this.mutex = new QMutex(QMutex::Recursive); }; - public void initialize(int instID) { - // QMutexLocker locker(mutex); + public synchronized void initialize(int instID) { this.instID = instID; } @@ -146,9 +146,8 @@ public abstract class UAVObject { * @throws Exception * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, + public synchronized void initializeFields(List fields, ByteBuffer data, int numBytes) { - // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; this.fields = fields; // Initialize fields @@ -267,15 +266,13 @@ public abstract class UAVObject { * Get the number of fields held by this object */ public int getNumFields() { - // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() { - // QMutexLocker locker(mutex); + public synchronized List getFields() { return fields; } @@ -286,7 +283,6 @@ public abstract class UAVObject { * @returns The field or NULL if not found */ public UAVObjectField getField(String name) { - // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); while (li.hasNext()) { @@ -307,8 +303,7 @@ public abstract class UAVObject { * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception { - // QMutexLocker locker(mutex); + public synchronized int pack(ByteBuffer dataOut) throws Exception { if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; @@ -329,7 +324,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; @@ -532,8 +527,17 @@ public abstract class UAVObject { /** * Java specific functions */ - public UAVObject clone() { - return (UAVObject) clone(); + public synchronized UAVObject clone() { + UAVObject newObj = clone(); + List newFields = new ArrayList(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField nf = li.next().clone(); + nf.initialize(newObj); + newFields.add(nf); + } + newObj.initializeFields(newFields, ByteBuffer.allocate(numBytes), numBytes); + return newObj; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 21444a04b..2fd7f7846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -617,6 +617,17 @@ public class UAVObjectField { return num; } + + @Override + public UAVObjectField clone() + { + UAVObjectField newField = new UAVObjectField(new String(name), new String(units), type, + new ArrayList(elementNames), + new ArrayList(options)); + newField.initialize(obj); + newField.data = data; + return newField; + } private String name; private String units; @@ -626,7 +637,7 @@ public class UAVObjectField { private int numElements; private int numBytesPerElement; private int offset; - private Object data; private UAVObject obj; + protected Object data; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 74ddb95fb..63f535eac 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -3,9 +3,29 @@ package org.openpilot.uavtalk; import java.util.ArrayList; import java.util.List; import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; public class UAVObjectManager { + public class CallbackListener extends Observable { + public void event (UAVObject obj) { + setChanged(); + notifyObservers(obj); + } + } + private CallbackListener newInstance = new CallbackListener(); + public void addNewInstanceObserver(Observer o) { + synchronized(newInstance) { + newInstance.addObserver(o); + } + } + private CallbackListener newObject = new CallbackListener(); + public void addNewObjectObserver(Observer o) { + synchronized(newObject) { + newObject.addObserver(o); + } + } private final int MAX_INSTANCES = 10; // Use array list to store objects since rarely added or deleted @@ -79,11 +99,12 @@ public class UAVObjectManager { UAVDataObject newObj = obj.clone(instID); newObj.initialize(mobj); instList.add(newObj); - // emit new instance signal + newInstance.event(newObj); } obj.initialize(mobj); //emit new instance signal instList.add(obj); + newInstance.event(obj); instIter = instList.listIterator(); while(instIter.hasNext()) { @@ -101,13 +122,13 @@ public class UAVObjectManager { UAVDataObject cobj = obj.clone(instId); cobj.initialize(mobj); instList.add(cobj); - // emit newInstance(cobj); + newInstance.event(cobj); } // Finally, initialize the actual object instance obj.initialize(mobj); // Add the actual object instance in the list instList.add(obj); - //emit newInstance(obj); + newInstance.event(obj); return true; } @@ -149,81 +170,67 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public synchronized List< List > getDataObjects() { - assert(false); // TOOD This - return new ArrayList>(); - - /* QMutexLocker locker(mutex); - QList< QList > dObjects; + List< List > dObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVDataObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVDataObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - dObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVDataObject) instIt.next()); } - }*/ + dObjects.add(newInstList); + } // Done + return dObjects; } /** * Same as getObjects() but will only return MetaObjects. */ - public List > getMetaObjects() + public synchronized List > getMetaObjects() { - assert(false); // TODO - return new ArrayList< List >(); - /* - QMutexLocker locker(mutex); - QList< QList > mObjects; + List< List > mObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVMetaObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - mObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(!instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVMetaObject) instIt.next()); } + mObjects.add(newInstList); } // Done return mObjects; - */ } @@ -270,7 +277,6 @@ public class UAVObjectManager { */ public synchronized UAVObject getObject(String name, int objId, int instId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { From cb5e690de058f077c997432446d299a0d012cd4b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:05:36 -0600 Subject: [PATCH 215/508] Most of the work on Telemetry.java as well as lots of signals for various object events --- .../src/org/openpilot/uavtalk/Telemetry.java | 623 +++++++++++++++++- .../openpilot/uavtalk/TelemetryMonitor.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 51 +- .../openpilot/uavtalk/UAVObjectManager.java | 3 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 7 +- 5 files changed, 673 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 88bc33de5..79e821fe3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,8 +1,18 @@ package org.openpilot.uavtalk; +import java.util.LinkedList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Queue; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.UAVObject.Acked; + public class Telemetry { - private TelemetryStats stats; public class TelemetryStats { public int txBytes; public int rxBytes; @@ -15,11 +25,612 @@ public class Telemetry { public int txRetries; } ; - public TelemetryStats getStats() { - return stats; - } + class ObjectTimeInfo { + UAVObject obj; + int updatePeriodMs; /** Update period in ms or 0 if no periodic updates are needed */ + int timeToNextUpdateMs; /** Time delay to the next update */ + }; + + class ObjectQueueInfo { + UAVObject obj; + int event; + boolean allInstances; + }; + + class ObjectTransactionInfo { + UAVObject obj; + boolean allInstances; + boolean objRequest; + int retriesRemaining; + Acked acked; + } ; - public void resetStats() { - stats = new TelemetryStats(); + /** + * Events generated by objects. Not enum because used in mask. + */ + private static final int EV_UNPACKED = 0x01; /** Object data updated by unpacking */ + private static final int EV_UPDATED = 0x02; /** Object data updated by changing the data structure */ + private static final int EV_UPDATED_MANUAL = 0x04; /** Object update event manually generated */ + private static final int EV_UPDATE_REQ = 0x08; /** Request to update object data */ + + /** + * Constructor + */ + public Telemetry(UAVTalk utalk, UAVObjectManager objMngr) + { + this.utalk = utalk; + this.objMngr = objMngr; + + // Process all objects in the list + List< List > objs = objMngr.getObjects(); + ListIterator> li = objs.listIterator(); + while(li.hasNext()) + registerObject(li.next().get(0)); // we only need to register one instance per object type + + // Listen to new object creations + objMngr.addNewInstanceObserver(new Observer() { + public void update(Observable observable, Object data) { + newInstance((UAVObject) data); + } + }); + objMngr.addNewObjectObserver(new Observer() { + public void update(Observable observable, Object data) { + newObject((UAVObject) data); + } + }); + + // Listen to transaction completions + utalk.addObserver(new Observer() { + public void update(Observable observable, Object data) { + transactionCompleted((UAVObject) data); + } + }); + + // Get GCS stats object + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + + // Setup transaction timer + transPending = false; + transTimer = new Timer(); + transTimerTask = new TimerTask() { + @Override + public void run() { + transactionTimeout(); + } + }; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + + updateTimer = new Timer(); + updateTimerTask = new TimerTask() { + @Override + public void run() { + processPeriodicUpdates(); + } + }; + updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; } + + /** + * Register a new object for periodic updates (if enabled) + */ + private void registerObject(UAVObject obj) + { + // Setup object for periodic updates + addObject(obj); + + // Setup object for telemetry updates + updateObject(obj); + } + + /** + * Add an object in the list used for periodic updates + */ + private void addObject(UAVObject obj) + { + // Check if object type is already in the list + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if( n.obj.getObjID() == obj.getObjID() ) + { + // Object type (not instance!) is already in the list, do nothing + return; + } + } + + // If this point is reached, then the object type is new, let's add it + ObjectTimeInfo timeInfo = new ObjectTimeInfo(); + timeInfo.obj = obj; + timeInfo.timeToNextUpdateMs = 0; + timeInfo.updatePeriodMs = 0; + objList.add(timeInfo); + } + + /** + * Update the object's timers + */ + private void setUpdatePeriod(UAVObject obj, int periodMs) + { + // Find object type (not instance!) and update its period + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if ( n.obj.getObjID() == obj.getObjID() ) + { + n.updatePeriodMs = periodMs; + n.timeToNextUpdateMs = (int) (periodMs * (new java.util.Random()).nextDouble()); // avoid bunching of updates + } + } + } + + /** + * Connect to all instances of an object depending on the event mask specified + */ + private void connectToObjectInstances(UAVObject obj, int eventMask) + { + List objs = objMngr.getObjectInstances(obj.getObjID()); + ListIterator li = objs.listIterator(); + while(li.hasNext()) + { + obj = li.next(); + //TODO: Disconnect all + // obj.disconnect(this); + + // Connect only the selected events + if ( (eventMask&EV_UNPACKED) != 0) + { + obj.addUnpackedObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUnpacked( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED) != 0) + { + obj.addUpdatedAutoObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedAuto( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED_MANUAL) != 0) + { + obj.addUpdatedManualObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedManual( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATE_REQ) != 0) + { + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + updateRequested( (UAVObject) data); + } + }); + } + } + } + + /** + * Update an object based on its metadata properties + */ + private void updateObject(UAVObject obj) + { + // Get metadata + UAVObject.Metadata metadata = obj.getMetadata(); + + // Setup object depending on update mode + int eventMask; + if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + { + // Set update period + setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Disconnect from object + connectToObjectInstances(obj, 0); + } + } + + /** + * Called when a transaction is successfully completed (uavtalk event) + */ + private void transactionCompleted(UAVObject obj) + { + // Check if there is a pending transaction and the objects match + if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) + { + // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + // Complete transaction + transTimer.cancel(); + transPending = false; + // Send signal + obj.transactionCompleted(true); + // Process new object updates from queue + processObjectQueue(); + } else + { + // qDebug() << "Error: received a transaction completed when did not expect it."; + } + } + + /** + * Called when a transaction is not completed within the timeout period (timer event) + */ + private void transactionTimeout() + { +// qDebug() << "Telemetry: transaction timeout."; + transTimer.cancel(); + // Proceed only if there is a pending transaction + if ( transPending ) + { + // Check if more retries are pending + if (transInfo.retriesRemaining > 0) + { + --transInfo.retriesRemaining; + processObjectTransaction(); + ++txRetries; + } + else + { + // Terminate transaction + utalk.cancelTransaction(); + transPending = false; + // Send signal + transInfo.obj.transactionCompleted(false); + // Process new object updates from queue + processObjectQueue(); + ++txErrors; + } + } + } + + /** + * Start an object transaction with UAVTalk, all information is stored in transInfo + */ + private void processObjectTransaction() + { + if (transPending) + { + // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + // Initiate transaction + if (transInfo.objRequest) + { + utalk.sendObjectRequest(transInfo.obj, transInfo.allInstances); + } + else + { + utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + } + // Start timer if a response is expected + if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + { + transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + } + else + { + transTimer.cancel(); + transPending = false; + } + } else + { + // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + } + } + + /** + * Process the event received from an object + */ + private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + { + // Push event into queue +// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + ObjectQueueInfo objInfo = new ObjectQueueInfo(); + objInfo.obj = obj; + objInfo.event = event; + objInfo.allInstances = allInstances; + if (priority) + { + if ( objPriorityQueue.size() < MAX_QUEUE_SIZE ) + { + objPriorityQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + } + } + else + { + if ( objQueue.size() < MAX_QUEUE_SIZE ) + { + objQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + } + } + + // If there is no transaction in progress then process event + if (!transPending) + { + // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else + { + // qDebug() << "Transaction pending, DO NOT process object queue..."; + } + } + + /** + * Process events from the object queue + */ + private void processObjectQueue() + { + // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + + // Don nothing if a transaction is already in progress (should not happen) + if (transPending) + { +// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + return; + } + + // Get object information from queue (first the priority and then the regular queue) + ObjectQueueInfo objInfo; + if ( !objPriorityQueue.isEmpty() ) + { + objInfo = objPriorityQueue.remove(); + } + else if ( !objQueue.isEmpty() ) + { + objInfo = objQueue.remove(); + } + else + { + return; + } + + // Check if a connection has been established, only process GCSTelemetryStats updates + // (used to establish the connection) + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) + { + objQueue.clear(); + if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) + { + objInfo.obj.transactionCompleted(false); + return; + } + } + + // Setup transaction (skip if unpack event) + if ( objInfo.event != EV_UNPACKED ) + { + UAVObject.Metadata metadata = objInfo.obj.getMetadata(); + transInfo.obj = objInfo.obj; + transInfo.allInstances = objInfo.allInstances; + transInfo.retriesRemaining = MAX_RETRIES; + transInfo.acked = metadata.gcsTelemetryAcked; + if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) + { + transInfo.objRequest = false; + } + else if ( objInfo.event == EV_UPDATE_REQ ) + { + transInfo.objRequest = true; + } + // Start transaction + transPending = true; + processObjectTransaction(); + } else + { +// qDebug() << QString("Process object queue: this is an unpack event for %1").arg(objInfo.obj->getName()); + } + + // If this is a metaobject then make necessary telemetry updates + if (objInfo.obj.isMetadata()) + { + UAVMetaObject metaobj = (UAVMetaObject) objInfo.obj; + updateObject( metaobj.getParentObject() ); + } + + // The fact we received an unpacked event does not mean that + // we do not have additional objects still in the queue, + // so we have to reschedule queue processing to make sure they are not + // stuck: + if ( objInfo.event == EV_UNPACKED ) + processObjectQueue(); + + } + + /** + * Check is any objects are pending for periodic updates + * TODO: Clean-up + */ + private synchronized void processPeriodicUpdates() + { + // Stop timer + updateTimer.cancel(); + + // Iterate through each object and update its timer, if zero then transmit object. + // Also calculate smallest delay to next update (will be used for setting timeToNextUpdateMs) + int minDelay = MAX_UPDATE_PERIOD_MS; + ObjectTimeInfo objinfo; + int elapsedMs = 0; + long startTime; + int offset; + ListIterator li = objList.listIterator(); + while(li.hasNext()) + { + objinfo = li.next(); + // If object is configured for periodic updates + if (objinfo.updatePeriodMs > 0) + { + objinfo.timeToNextUpdateMs -= timeToNextUpdateMs; + // Check if time for the next update + if (objinfo.timeToNextUpdateMs <= 0) + { + // Reset timer + offset = (-objinfo.timeToNextUpdateMs) % objinfo.updatePeriodMs; + objinfo.timeToNextUpdateMs = objinfo.updatePeriodMs - offset; + // Send object + startTime = System.currentTimeMillis(); + processObjectUpdates(objinfo.obj, EV_UPDATED_MANUAL, true, false); + elapsedMs = (int) (System.currentTimeMillis() - startTime); + // Update timeToNextUpdateMs with the elapsed delay of sending the object; + timeToNextUpdateMs += elapsedMs; + } + // Update minimum delay + if (objinfo.timeToNextUpdateMs < minDelay) + { + minDelay = objinfo.timeToNextUpdateMs; + } + } + } + + // Check if delay for the next update is too short + if (minDelay < MIN_UPDATE_PERIOD_MS) + { + minDelay = MIN_UPDATE_PERIOD_MS; + } + + // Done + timeToNextUpdateMs = minDelay; + + // Restart timer + //updateTimer->start(timeToNextUpdateMs); + updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + } + + public TelemetryStats getStats() + { + // Get UAVTalk stats + UAVTalk.ComStats utalkStats = utalk.getStats(); + + // Update stats + TelemetryStats stats = new TelemetryStats(); + stats.txBytes = utalkStats.txBytes; + stats.rxBytes = utalkStats.rxBytes; + stats.txObjectBytes = utalkStats.txObjectBytes; + stats.rxObjectBytes = utalkStats.rxObjectBytes; + stats.rxObjects = utalkStats.rxObjects; + stats.txObjects = utalkStats.txObjects; + stats.txErrors = utalkStats.txErrors + txErrors; + stats.rxErrors = utalkStats.rxErrors; + stats.txRetries = txRetries; + + // Done + return stats; + } + + public synchronized void resetStats() + { + utalk.resetStats(); + txErrors = 0; + txRetries = 0; + } + + private synchronized void objectUpdatedAuto(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED, false, true); + } + + private synchronized void objectUpdatedManual(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED_MANUAL, false, true); + } + + private synchronized void objectUnpacked(UAVObject obj) + { + processObjectUpdates(obj, EV_UNPACKED, false, true); + } + + private synchronized void updateRequested(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATE_REQ, false, true); + } + + private void newObject(UAVObject obj) + { + registerObject(obj); + } + + private synchronized void newInstance(UAVObject obj) + { + registerObject(obj); + } + + /** + * Private variables + */ + private TelemetryStats stats; + private UAVObjectManager objMngr; + private UAVTalk utalk; + private UAVObject gcsStatsObj; + private List objList; + private Queue objQueue = new LinkedList(); + private Queue objPriorityQueue = new LinkedList(); + private ObjectTransactionInfo transInfo; + private boolean transPending; + + private Timer updateTimer; + private TimerTask updateTimerTask; + private Timer transTimer; + private TimerTask transTimerTask; + + private int timeToNextUpdateMs; + private int txErrors; + private int txRetries; + + /** + * Private constants + */ + private static final int REQ_TIMEOUT_MS = 250; + private static final int MAX_RETRIES = 2; + private static final int MAX_UPDATE_PERIOD_MS = 1000; + private static final int MIN_UPDATE_PERIOD_MS = 1; + private static final int MAX_QUEUE_SIZE = 20; + + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 40fc220cc..39d332457 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -123,7 +123,7 @@ public class TelemetryMonitor { // Connect to object //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); // Request update - obj.requestUpdate(); + tel.requestUpdate(obj); objPending = obj; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index adfece03e..9e4f69a39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -8,7 +8,7 @@ import java.util.Observer; import java.util.Observable; public abstract class UAVObject { - + public class CallbackListener extends Observable { private UAVObject parent; @@ -20,6 +20,31 @@ public abstract class UAVObject { setChanged(); notifyObservers(parent); } + public void event (Object data) { + setChanged(); + notifyObservers(data); + } + } + + public class TransactionResult { + public UAVObject obj; + public boolean success; + public TransactionResult(UAVObject obj, boolean success) { + this.obj = obj; + this.success = success; + } + } + + private CallbackListener transactionCompletedListeners = new CallbackListener(this); + public void addTransactionCompleted(Observer o) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.addObserver(o); + } + } + void transactionCompleted(boolean status) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.event(new TransactionResult(this,status)); + } } private CallbackListener updatedListeners = new CallbackListener(this); @@ -47,6 +72,30 @@ public abstract class UAVObject { } } + private CallbackListener updatedAutoListeners = new CallbackListener(this); + public void addUpdatedAutoObserver(Observer o) { + synchronized(updatedAutoListeners) { + updatedAutoListeners.addObserver(o); + } + } + void updatedAuto() { + synchronized(updatedAutoListeners) { + updatedAutoListeners.event(); + } + } + + private CallbackListener updatedManualListeners = new CallbackListener(this); + public void addUpdatedManualObserver(Observer o) { + synchronized(updatedManualListeners) { + updatedManualListeners.addObserver(o); + } + } + void updatedManual() { + synchronized(updatedManualListeners) { + updatedManualListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 63f535eac..3ec588879 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -102,7 +102,6 @@ public class UAVObjectManager { newInstance.event(newObj); } obj.initialize(mobj); - //emit new instance signal instList.add(obj); newInstance.event(obj); @@ -155,7 +154,7 @@ public class UAVObjectManager { List ls = new ArrayList(); ls.add(obj); objects.add(ls); - //emit newObject(obj); + newObject.event(obj); } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 7ea9c7c60..847b7c425 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -7,8 +7,9 @@ import java.io.InputStream; import java.io.OutputStream; import java.nio.ByteBuffer; import java.nio.ByteOrder; +import java.util.Observable; -public class UAVTalk { +public class UAVTalk extends Observable{ private Thread inputProcessingThread = null; /** @@ -632,8 +633,8 @@ public class UAVTalk { if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; - // TODO: Signals -// emit transactionCompleted(obj); + setChanged(); + notifyObservers(obj); } } From 55e08340514c85bb93929b8d8ffcb72113609afc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:39:33 -0600 Subject: [PATCH 216/508] Changes to TelemetryMonitor, ready for testing --- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 54 +++++++++++-------- 2 files changed, 32 insertions(+), 24 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 79e821fe3..4bed72fea 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -585,7 +585,7 @@ public class Telemetry { processObjectUpdates(obj, EV_UNPACKED, false, true); } - private synchronized void updateRequested(UAVObject obj) + public synchronized void updateRequested(UAVObject obj) { processObjectUpdates(obj, EV_UPDATE_REQ, false, true); } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 39d332457..dabbf1d4b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -28,6 +28,7 @@ public class TelemetryMonitor { private UAVObject flightStatsObj; private Timer periodicTask; private int currentPeriod; + private long lastUpdateTime; private List queue; public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) @@ -121,9 +122,15 @@ public class TelemetryMonitor { Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object - //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + obj.addTransactionCompleted(new Observer() { + public void update(Observable observable, Object data) { + UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + transactionCompleted(result.obj, result.success); + } + }); + // Request update - tel.requestUpdate(obj); + tel.updateRequested(obj); objPending = obj; } @@ -184,9 +191,10 @@ public class TelemetryMonitor { boolean connectionTimeout; if ( telStats.rxObjects > 0 ) { - //connectionTimer.start(); + lastUpdateTime = System.currentTimeMillis(); + } - if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + if ( (System.currentTimeMillis() - lastUpdateTime) > CONNECTION_TIMEOUT_MS ) { connectionTimeout = true; } @@ -196,53 +204,53 @@ public class TelemetryMonitor { } // Update connection state - int oldStatus = gcsStats.Status; - if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + UAVObjectField statusField = gcsStatsObj.getField("Connection"); + String oldStatus = (String) statusField.getValue(); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection - gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + statusField.setValue("HandshakeReq"); } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + else if ( oldStatus.compareTo("HandshakeReq") == 0 ) { // Check for connection acknowledge - if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { - gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + statusField.setValue("Connected"); } } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + else if ( oldStatus.compareTo("Connected") == 0 ) { // Check if the connection is still active and the the autopilot is still connected - if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") == 0 || connectionTimeout) { - gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + statusField.setValue("Disconnected"); } } - // Set data - gcsStatsObj->setData(gcsStats); - // Force telemetry update if not yet connected - if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || - flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; + boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + if ( gcsStatusChanged || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { - gcsStatsObj->updated(); + gcsStatsObj.updated(); } // Act on new connections or disconnections - if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } - if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); Log.d(TAG,"Connection with the autopilot lost"); Log.d(TAG,"Trying to connect to the autopilot"); - emit disconnected(); + //emit disconnected(); } } From 7b20773100121e15afc07edfe85245e3846c94a8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:27 -0600 Subject: [PATCH 217/508] Fixed bug in object signals that stopped updates sending. Various tweaks. --- .../src/org/openpilot/uavtalk/Telemetry.java | 33 ++++++++++------- .../openpilot/uavtalk/TelemetryMonitor.java | 35 +++++++++++++++---- .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 8 +++-- .../org/openpilot/uavtalk/UAVObjectField.java | 4 +-- .../src/org/openpilot/uavtalk/UAVTalk.java | 15 +++++--- 6 files changed, 68 insertions(+), 29 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 4bed72fea..d2f82459b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,5 +1,6 @@ package org.openpilot.uavtalk; +import java.util.ArrayList; import java.util.LinkedList; import java.util.List; import java.util.ListIterator; @@ -91,6 +92,15 @@ public class Telemetry { // Setup transaction timer transPending = false; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + updateTimerSetPeriod(1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; + } + + synchronized void transTimerSetPeriod(int periodMs) { transTimer = new Timer(); transTimerTask = new TimerTask() { @Override @@ -98,9 +108,10 @@ public class Telemetry { transactionTimeout(); } }; - // Setup and start the periodic timer - timeToNextUpdateMs = 0; - + transTimer.schedule(transTimerTask, periodMs, periodMs); + } + + synchronized void updateTimerSetPeriod(int periodMs) { updateTimer = new Timer(); updateTimerTask = new TimerTask() { @Override @@ -108,10 +119,8 @@ public class Telemetry { processPeriodicUpdates(); } }; - updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); - // Setup and start the stats timer - txErrors = 0; - txRetries = 0; + updateTimer.schedule(updateTimerTask, periodMs, periodMs); + } /** @@ -341,7 +350,7 @@ public class Telemetry { // Start timer if a response is expected if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) { - transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + transTimerSetPeriod(REQ_TIMEOUT_MS); } else { @@ -433,6 +442,7 @@ public class Telemetry { // Check if a connection has been established, only process GCSTelemetryStats updates // (used to establish the connection) + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) { objQueue.clear(); @@ -538,8 +548,7 @@ public class Telemetry { timeToNextUpdateMs = minDelay; // Restart timer - //updateTimer->start(timeToNextUpdateMs); - updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + updateTimerSetPeriod(timeToNextUpdateMs); } public TelemetryStats getStats() @@ -607,10 +616,10 @@ public class Telemetry { private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; - private List objList; + private List objList = new ArrayList(); private Queue objQueue = new LinkedList(); private Queue objPriorityQueue = new LinkedList(); - private ObjectTransactionInfo transInfo; + private ObjectTransactionInfo transInfo = new ObjectTransactionInfo(); private boolean transPending; private Timer updateTimer; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index dabbf1d4b..bc0bfd6eb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -92,7 +92,7 @@ public class TelemetryMonitor { } } // Start retrieving - Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + System.out.println(TAG + "Starting to retrieve meta and settings objects from the autopilot (" + queue.size() + " objects)"); retrieveNextObject(); } @@ -120,7 +120,7 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); - Log.d(TAG, "Retrieving object: " + obj.getName()) ; +// Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -161,6 +161,10 @@ public class TelemetryMonitor { public synchronized void flightStatsUpdated(UAVObject obj) { // Force update if not yet connected + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -204,8 +208,17 @@ public class TelemetryMonitor { } // Update connection state - UAVObjectField statusField = gcsStatsObj.getField("Connection"); + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + if(gcsStatsObj == null) { + System.out.println("No GCS stats yet"); + return; + } + UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = (String) statusField.getValue(); + + System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection @@ -217,6 +230,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); + System.out.println("Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -230,11 +244,18 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + + if(gcsStatusChanged) + System.out.println("GCS Status changed"); boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + + if(gcsConnected) + System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { + System.out.println("Sending gcs status\n\n\n"); gcsStatsObj.updated(); } @@ -242,14 +263,15 @@ public class TelemetryMonitor { if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot established"); + System.out.println(TAG + " Connection with the autopilot established"); + //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot lost"); - Log.d(TAG,"Trying to connect to the autopilot"); + System.out.println(TAG + " Connection with the autopilot lost"); + //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } @@ -260,6 +282,7 @@ public class TelemetryMonitor { periodicTask.cancel(); currentPeriod = ms; + periodicTask = new Timer(); periodicTask.scheduleAtFixedRate(new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 5694cc9d8..0acc02226 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,7 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } - public boolean isMetadata() { return true; }; + public boolean isMetadata() { return false; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 9e4f69a39..fac67cabc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -53,11 +53,14 @@ public abstract class UAVObject { updatedListeners.addObserver(o); } } - void updated() { + void updated(boolean manually) { synchronized(updatedListeners) { updatedListeners.event(); } + if(manually) + updatedManual(); } + void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { @@ -67,7 +70,6 @@ public abstract class UAVObject { } void unpacked() { synchronized(unpackedListeners) { - System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); unpackedListeners.event(); } } @@ -387,7 +389,7 @@ public abstract class UAVObject { // Trigger all the listeners for the unpack event unpacked(); - updated(); + updated(false); return numBytes; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 2fd7f7846..8d792bb39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -131,7 +131,7 @@ public class UAVObjectField { case UINT32: // TODO: Deal properly with unsigned for (int index = 0; index < numElements; ++index) { - Integer val = (Integer) getValue(index); + Integer val = (int) ( ((Long) getValue(index)).longValue() & 0xffffffffL); dataOut.putInt(val); } break; @@ -364,7 +364,7 @@ public class UAVObjectField { public double getDouble() { return getDouble(0); }; public double getDouble(int index) { - return Double.valueOf((Double) getValue(index)); + return ((Number) getValue(index)).doubleValue(); } public void setDouble(double value) { setDouble(value, 0); }; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 847b7c425..8576be78c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -200,9 +200,9 @@ public class UAVTalk extends Observable{ * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - //QMutexLocker locker(mutex); + System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -216,9 +216,8 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public void cancelTransaction() + public synchronized void cancelTransaction() { - //QMutexLocker locker(mutex); respObj = null; } @@ -250,6 +249,7 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { + System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -763,7 +763,12 @@ public class UAVTalk extends Observable{ bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); try { - outStream.write(bbuf.array()); + int packlen = bbuf.position(); + bbuf.position(0); + byte [] dst = new byte[packlen]; + bbuf.get(dst,0,packlen); + System.out.println("Outputting: " + dst.length); + outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); From 621d31a52025d3a208862ac90c15222d0059cd65 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:59 -0600 Subject: [PATCH 218/508] Unit test for telemetry --- .../uavtalk/TelemetryMonitorTest.java | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java new file mode 100644 index 000000000..1fc02d145 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java @@ -0,0 +1,64 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TelemetryMonitorTest { + + static UAVObjectManager objMngr; + static UAVTalk talk; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 7777; + static Socket connection = null; + boolean succeed = false; + + @Test + public void testTelemetry() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(talk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + Thread.sleep(10000); + + System.out.println("Done"); + } + + +} From e12cef6b4bb99707366555d962ed24047eb7649c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 13:44:40 -0600 Subject: [PATCH 219/508] Little updates --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 56 ++++++++++++++----- 2 files changed, 51 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8576be78c..92b5585de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -202,7 +202,6 @@ public class UAVTalk extends Observable{ */ public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -249,7 +248,6 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { - System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -263,7 +261,7 @@ public class UAVTalk extends Observable{ * \param[in] rxbyte Received byte * \return Success (true), Failure (false) */ - public boolean processInputByte(int rxbyte) + public synchronized boolean processInputByte(int rxbyte) { assert(objMngr != null); @@ -448,12 +446,10 @@ public class UAVTalk extends Observable{ break; } - //mutex->lock(); rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; stats.rxObjects++; - //mutex->unlock(); rxState = RxStateType.STATE_SYNC; break; @@ -484,13 +480,13 @@ public class UAVTalk extends Observable{ boolean error = false; boolean allInstances = (instId == ALL_INSTANCES? true : false); - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages if (!allInstances) { + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -512,6 +508,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { + System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -531,6 +528,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object + System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -553,6 +551,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { + System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -578,7 +577,7 @@ public class UAVTalk extends Observable{ * If the object instance could not be found in the list, then a * new one is created. */ - public UAVObject updateObject(int objId, int instId, ByteBuffer data) + public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) { assert(objMngr != null); @@ -613,13 +612,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } + System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 252927122..044ddfd06 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -1,10 +1,13 @@ package org.openpilot.uavtalk; import static org.junit.Assert.*; +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.InputStreamReader; import java.io.OutputStream; +import java.io.OutputStreamWriter; import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; @@ -31,7 +34,7 @@ public class TalkTest { UAVObjectsInitialize.register(objMngr); } - @Test + //@Test public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; @@ -78,22 +81,49 @@ public class TalkTest { @Test public void testSendObjectRequest() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + + talk.sendObject(obj, false, false); + + System.out.println("Size: " + os.size()); + byte [] array = os.toByteArray(); + for(int i = 0; i < array.length; i++) { + System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + if(i != array.length-1) + System.out.print(", "); + } + System.out.print("\n"); } - - @Test - public void testSendObject() { - fail("Not yet implemented"); - } - + @Test public void testReceiveObject() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + // Send object to create the test packet (should hard code in test string) + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + talk.sendObject(obj, false, false); + + obj.getField("Status").setValue("Disconnected"); + + // Test receiving from that stream + is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); + talk = new UAVTalk(is,os,objMngr); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + System.out.println("Should be FlightTelemetry Stats:"); + System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); + + fail("Not working yet"); } - @Test - public void testUpdateObject() { - fail("Not yet implemented"); - } } From 03b9bbbb8ace148c45581b71731a0684d4e166a8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 14:36:37 -0600 Subject: [PATCH 220/508] Fix the CRC calculation for java sending --- .../src/org/openpilot/uavtalk/UAVTalk.java | 13 ++++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 34 ++++++++++++------- 2 files changed, 31 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 92b5585de..d656aa707 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -175,7 +175,12 @@ public class UAVTalk extends Observable{ e.printStackTrace(); break; } - //System.out.println("Received byte " + val + " in state + " + rxState); + if(val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + break; + } + + System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -760,7 +765,7 @@ public class UAVTalk extends Observable{ } // Calculate checksum - bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + bbuf.put((byte) (updateCRC(0, bbuf.array(), bbuf.position()) & 0xff)); try { int packlen = bbuf.position(); @@ -818,9 +823,9 @@ public class UAVTalk extends Observable{ { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data) + int updateCRC(int crc, byte [] data, int length) { - for (int i = 0; i < data.length; i++) + for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); return crc; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 044ddfd06..91f3aa198 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -28,6 +28,16 @@ public class TalkTest { static final int PORT_NUM = 7777; boolean succeed = false; + byte[] flightStatsConnected = + {0x3c,0x20,0x1d,0x00, + (byte) 0x5e,(byte) 0x26,(byte) 0x0c,(byte) 0x66, + 0x03,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,(byte) 0xAE}; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -89,40 +99,40 @@ public class TalkTest { obj.getField("Status").setValue("Connected"); talk.sendObject(obj, false, false); - + System.out.println("Size: " + os.size()); byte [] array = os.toByteArray(); for(int i = 0; i < array.length; i++) { System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + System.out.print("/0x" + Integer.toHexString((int) flightStatsConnected[i] & 0xff)); if(i != array.length-1) - System.out.print(", "); + System.out.print("\n"); } System.out.print("\n"); + for(int i = 0; i < array.length; i++) + assertEquals(os.toByteArray()[i], flightStatsConnected[i]); } @Test - public void testReceiveObject() { - ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + public void testReceiveObject() throws InterruptedException { + ByteArrayInputStream is = new ByteArrayInputStream(flightStatsConnected, 0, flightStatsConnected.length); ByteArrayOutputStream os = new ByteArrayOutputStream(100); - // Send object to create the test packet (should hard code in test string) - UAVTalk talk = new UAVTalk(is,os,objMngr); + // Make the Status wrong initially UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.getField("Status").setValue("Connected"); - talk.sendObject(obj, false, false); - obj.getField("Status").setValue("Disconnected"); // Test receiving from that stream - is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); - talk = new UAVTalk(is,os,objMngr); + UAVTalk talk = new UAVTalk(is,os,objMngr); Thread inputStream = talk.getInputProcessThread(); inputStream.start(); + Thread.sleep(1000); + System.out.println("Should be FlightTelemetry Stats:"); System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); - fail("Not working yet"); + assertEquals(obj.getField("Status").getValue(), new String("Connected")); } From 06f583ff754a0813171e789451cb95f7f6bb497e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 21:36:09 -0600 Subject: [PATCH 221/508] Fixed some timer issues. Got connection with this. --- .../src/org/openpilot/uavtalk/Telemetry.java | 9 ++++++++- .../org/openpilot/uavtalk/TelemetryMonitor.java | 3 --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++++++--------- 3 files changed, 15 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index d2f82459b..7f04e344b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -101,7 +101,14 @@ public class Telemetry { } synchronized void transTimerSetPeriod(int periodMs) { - transTimer = new Timer(); + if(transTimerTask != null) + transTimerTask.cancel(); + + if(transTimer != null) + transTimer.purge(); + + transTimer = new Timer(); + transTimerTask = new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index bc0bfd6eb..eb406923d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -164,7 +164,6 @@ public class TelemetryMonitor { gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -250,8 +249,6 @@ public class TelemetryMonitor { boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - if(gcsConnected) - System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index d656aa707..825f9d9fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -180,7 +180,7 @@ public class UAVTalk extends Observable{ break; } - System.out.println("Received byte " + val + " in state + " + rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -423,7 +423,6 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - //System.out.println(rxCount + "/" + rxLength); rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); if (rxCount < rxLength) break; @@ -491,7 +490,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ messages if (!allInstances) { - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + System.out.println("Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -513,7 +512,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -533,7 +532,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object - System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -556,7 +555,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -617,14 +616,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } - System.out.println("Unpacking new object"); +// System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); +// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } @@ -772,7 +771,6 @@ public class UAVTalk extends Observable{ bbuf.position(0); byte [] dst = new byte[packlen]; bbuf.get(dst,0,packlen); - System.out.println("Outputting: " + dst.length); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block From bd0a599e9687ecfa4d22e33c6a0b49b1b8e07dbe Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 13 Mar 2011 21:01:11 -0500 Subject: [PATCH 222/508] Works on Nook, but recursive loop too deep in registering objects --- androidgcs/AndroidManifest.xml | 12 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/main.xml | 1 - androidgcs/res/values/strings.xml | 1 - .../openpilot/androidgcs/ObjectBrowser.java | 129 ++++++++++++++++++ .../src/org/openpilot/uavtalk/Telemetry.java | 47 ++++--- .../openpilot/uavtalk/TelemetryMonitor.java | 15 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 +- 8 files changed, 186 insertions(+), 33 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 7a96a6600..8b3a9e4b3 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -5,8 +5,18 @@ android:versionName="1.0"> - + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 46769a720..66db0d159 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-7 +target=android-10 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 3a5f117d3..7e4a852bf 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -7,6 +7,5 @@ diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 0d9f93bc2..52fa56534 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,5 +1,4 @@ - Hello World! OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..3c6231258 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,129 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.Intent; +import android.os.Bundle; +import android.util.Log; + +import org.openpilot.androidgcs.*; +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjectBrowser extends Activity { + + private final String TAG = "ObjectBrower"; + private final String DEVICE_NAME = "RN42-222D"; + private final int REQUEST_ENABLE_BT = 0; + private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + BluetoothAdapter mBluetoothAdapter; + UAVObjectManager objMngr; + UAVTalk uavTalk; + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + + Log.d(TAG, "Launching Object Browser"); + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.d(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); + } else { + queryDevices(); + } + } + + @Override + public void onActivityResult(int requestCode, int resultCode, Intent data) { + if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { + Log.d(TAG, "Bluetooth started succesfully"); + queryDevices(); + } + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) + Log.d(TAG, "Bluetooth could not be started"); + + } + + public void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + openTelmetryBluetooth(device); + openTelmetryBluetooth(device); + } + } + } + + } + + private void openTelmetryBluetooth(BluetoothDevice device) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + BluetoothSocket socket = null; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return; + } + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + e.printStackTrace(); + return; + } + + Thread inputStream = uavTalk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(uavTalk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 7f04e344b..b403f85e3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -12,8 +12,12 @@ import java.util.TimerTask; import org.openpilot.uavtalk.UAVObject.Acked; +import android.util.Log; + public class Telemetry { + private final String TAG = "Telemetry"; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -133,7 +137,7 @@ public class Telemetry { /** * Register a new object for periodic updates (if enabled) */ - private void registerObject(UAVObject obj) + private synchronized void registerObject(UAVObject obj) { // Setup object for periodic updates addObject(obj); @@ -145,7 +149,7 @@ public class Telemetry { /** * Add an object in the list used for periodic updates */ - private void addObject(UAVObject obj) + private synchronized void addObject(UAVObject obj) { // Check if object type is already in the list ListIterator li = objList.listIterator(); @@ -169,7 +173,7 @@ public class Telemetry { /** * Update the object's timers */ - private void setUpdatePeriod(UAVObject obj, int periodMs) + private synchronized void setUpdatePeriod(UAVObject obj, int periodMs) { // Find object type (not instance!) and update its period ListIterator li = objList.listIterator(); @@ -186,7 +190,7 @@ public class Telemetry { /** * Connect to all instances of an object depending on the event mask specified */ - private void connectToObjectInstances(UAVObject obj, int eventMask) + private synchronized void connectToObjectInstances(UAVObject obj, int eventMask) { List objs = objMngr.getObjectInstances(obj.getObjID()); ListIterator li = objs.listIterator(); @@ -235,7 +239,7 @@ public class Telemetry { /** * Update an object based on its metadata properties */ - private void updateObject(UAVObject obj) + private synchronized void updateObject(UAVObject obj) { // Get metadata UAVObject.Metadata metadata = obj.getMetadata(); @@ -287,12 +291,12 @@ public class Telemetry { /** * Called when a transaction is successfully completed (uavtalk event) */ - private void transactionCompleted(UAVObject obj) + private synchronized void transactionCompleted(UAVObject obj) { // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -302,16 +306,16 @@ public class Telemetry { processObjectQueue(); } else { - // qDebug() << "Error: received a transaction completed when did not expect it."; + Log.e(TAG,"Error: received a transaction completed when did not expect it."); } } /** * Called when a transaction is not completed within the timeout period (timer event) */ - private void transactionTimeout() + private synchronized void transactionTimeout() { -// qDebug() << "Telemetry: transaction timeout."; + Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -340,11 +344,11 @@ public class Telemetry { /** * Start an object transaction with UAVTalk, all information is stored in transInfo */ - private void processObjectTransaction() + private synchronized void processObjectTransaction() { if (transPending) { - // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -366,17 +370,17 @@ public class Telemetry { } } else { - // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + Log.e(TAG,"Error: inside of processObjectTransaction with no transPending"); } } /** * Process the event received from an object */ - private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue -// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -391,7 +395,7 @@ public class Telemetry { { ++txErrors; obj.transactionCompleted(false); - //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + Log.w(TAG,"Telemetry: priority event queue is full, event lost " + obj.getName()); } } else @@ -410,25 +414,26 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else { - // qDebug() << "Transaction pending, DO NOT process object queue..."; + Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } /** * Process events from the object queue */ - private void processObjectQueue() + private synchronized void processObjectQueue() { - // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) { -// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + Log.e(TAG,"Dequeue while a transaction pending"); return; } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index eb406923d..e2050fc25 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -55,7 +55,7 @@ public class TelemetryMonitor { /** * Initiate object retrieval, initialize queue with objects to be retrieved. */ - public void startRetrievingObjects() + public synchronized void startRetrievingObjects() { // Clear object queue queue.clear(); @@ -108,7 +108,7 @@ public class TelemetryMonitor { /** * Retrieve the next object in the queue */ - public void retrieveNextObject() + public synchronized void retrieveNextObject() { // If queue is empty return if ( queue.isEmpty() ) @@ -120,7 +120,12 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); -// Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if(obj == null) { + Log.e(TAG, "Got null object forom transaction queue"); + return; + } + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -137,10 +142,12 @@ public class TelemetryMonitor { /** * Called by the retrieved object when a transaction is completed. */ - public void transactionCompleted(UAVObject obj, boolean success) + public synchronized void transactionCompleted(UAVObject obj, boolean success) { //QMutexLocker locker(mutex); // Disconnect from sending object + Log.d(TAG,"transactionCompleted"); + // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fac67cabc..b74df9218 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -17,12 +17,16 @@ public abstract class UAVObject { } public void event () { - setChanged(); - notifyObservers(parent); + synchronized(this) { + setChanged(); + notifyObservers(parent); + } } public void event (Object data) { - setChanged(); - notifyObservers(data); + synchronized(this) { + setChanged(); + notifyObservers(data); + } } } From 77910a93ab1df0687180fb69a6c24ec9747f2d5f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:18:45 -0500 Subject: [PATCH 223/508] Update display to show connected icon --- androidgcs/res/drawable-hdpi/icon.png | Bin 4147 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 1723 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 2574 -> 48558 bytes androidgcs/res/layout/main.xml | 2 + .../openpilot/androidgcs/ObjectBrowser.java | 92 +++++++++++++++--- 5 files changed, 83 insertions(+), 11 deletions(-) diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index 8074c4c571b8cd19e27f4ee5545df367420686d7..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index 1095584ec21f71cd0afc9e0993aa2209671b590c..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(h + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 3c6231258..a8c58d58d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,6 +1,8 @@ package org.openpilot.androidgcs; import java.io.IOException; +import java.util.Observable; +import java.util.Observer; import java.util.Set; import java.util.UUID; @@ -10,11 +12,15 @@ import android.bluetooth.BluetoothDevice; import android.bluetooth.BluetoothSocket; import android.content.Intent; import android.os.Bundle; +import android.os.Handler; import android.util.Log; +import android.widget.TextView; +import android.widget.ToggleButton; import org.openpilot.androidgcs.*; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -26,9 +32,35 @@ public class ObjectBrowser extends Activity { private final int REQUEST_ENABLE_BT = 0; private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); BluetoothAdapter mBluetoothAdapter; + BluetoothSocket socket; + boolean connected; UAVObjectManager objMngr; UAVTalk uavTalk; + final Handler uavobjHandler = new Handler(); + final Runnable updateText = new Runnable() { + public void run() { + ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); + button.setChecked(!connected); + + Log.d(TAG,"HERE" + connected); + + TextView text = (TextView) findViewById(R.id.textView1); + + UAVObject obj1 = objMngr.getObject("SystemStats"); + UAVObject obj2 = objMngr.getObject("AttitudeRaw"); + UAVObject obj3 = objMngr.getObject("AttitudeActual"); + UAVObject obj4 = objMngr.getObject("SystemAlarms"); + + if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) + return; + + Log.d(TAG,"And here"); + text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); + + } + }; + /** Called when the activity is first created. */ @Override public void onCreate(Bundle savedInstanceState) { @@ -36,11 +68,16 @@ public class ObjectBrowser extends Activity { setContentView(R.layout.main); Log.d(TAG, "Launching Object Browser"); + + connected = false; + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); if (mBluetoothAdapter == null) { // Device does not support Bluetooth - Log.d(TAG, "Device does not support Bluetooth"); + Log.e(TAG, "Device does not support Bluetooth"); return; } @@ -50,16 +87,49 @@ public class ObjectBrowser extends Activity { } else { queryDevices(); } + + + UAVObject obj = objMngr.getObject("SystemStats"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeRaw"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("SystemAlarms"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + + } @Override public void onActivityResult(int requestCode, int resultCode, Intent data) { if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - Log.d(TAG, "Bluetooth started succesfully"); + //Log.d(TAG, "Bluetooth started succesfully"); queryDevices(); } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) - Log.d(TAG, "Bluetooth could not be started"); + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { + //Log.d(TAG, "Bluetooth could not be started"); + } } @@ -84,12 +154,13 @@ public class ObjectBrowser extends Activity { private void openTelmetryBluetooth(BluetoothDevice device) { Log.d(TAG, "Opening conncetion to " + device.getName()); - BluetoothSocket socket = null; + socket = null; + connected = false; try { socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); } catch (IOException e) { Log.e(TAG,"Unable to create Rfcomm socket"); - e.printStackTrace(); + //e.printStackTrace(); } mBluetoothAdapter.cancelDiscovery(); @@ -102,20 +173,19 @@ public class ObjectBrowser extends Activity { try { socket.close(); } catch (IOException e2) { - Log.e(TAG, "unable to close() socket during connection failure", e2); + //Log.e(TAG, "unable to close() socket during connection failure", e2); } return; } - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - + connected = true; + try { uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); } catch (IOException e) { Log.e(TAG,"Error starting UAVTalk"); // TODO Auto-generated catch block - e.printStackTrace(); + //e.printStackTrace(); return; } From 74ea0e5ac2c8b418234793de87952d40bc5bdfdb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:19:18 -0500 Subject: [PATCH 224/508] Make it easy to enable or disable logging in separate modules --- .../src/org/openpilot/uavtalk/Telemetry.java | 30 +- .../openpilot/uavtalk/TelemetryMonitor.java | 41 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 + .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 593 ++++++++---------- 5 files changed, 324 insertions(+), 354 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index b403f85e3..c754c8329 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,10 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -227,7 +230,7 @@ public class Telemetry { } if ( (eventMask&EV_UPDATE_REQ) != 0) { - obj.addUpdatedObserver(new Observer() { + obj.addUpdateRequestedObserver(new Observer() { public void update(Observable observable, Object data) { updateRequested( (UAVObject) data); } @@ -293,10 +296,11 @@ public class Telemetry { */ private synchronized void transactionCompleted(UAVObject obj) { + if (DEBUG) Log.d(TAG,"UAVTalk transactionCompleted"); // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); + if (DEBUG) Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -315,7 +319,7 @@ public class Telemetry { */ private synchronized void transactionTimeout() { - Log.d(TAG,"Telemetry: transaction timeout."); + if (DEBUG) Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -348,7 +352,7 @@ public class Telemetry { { if (transPending) { - Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); + if (DEBUG) Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -380,7 +384,9 @@ public class Telemetry { private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue - Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if (DEBUG) Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if(event == 8 && obj.getName().compareTo("GCSTelemetryStats") == 0) + Thread.dumpStack(); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -414,12 +420,7 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - processObjectQueue(); - - } else - { - Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } @@ -428,7 +429,7 @@ public class Telemetry { */ private synchronized void processObjectQueue() { - Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); + if (DEBUG) Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) @@ -460,6 +461,9 @@ public class Telemetry { objQueue.clear(); if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) { + if (DEBUG) Log.d(TAG,"transactionCompleted(false) due to receiving object not GCSTelemetryStats while not connected."); + System.out.println(gcsStatsObj.toString()); + System.out.println(objInfo.obj.toString()); objInfo.obj.transactionCompleted(false); return; } @@ -511,6 +515,8 @@ public class Telemetry { */ private synchronized void processPeriodicUpdates() { + + if (DEBUG) Log.d(TAG, "processPeriodicUpdates()"); // Stop timer updateTimer.cancel(); diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index e2050fc25..a5885e7bc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -57,6 +57,8 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { + Log.d(TAG, "Start retrieving objects"); + // Clear object queue queue.clear(); // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue @@ -101,7 +103,7 @@ public class TelemetryMonitor { */ public void stopRetrievingObjects() { - //qxtLog->debug("Object retrieval has been cancelled"); + Log.d(TAG, "Stop retrieving objects"); queue.clear(); } @@ -113,6 +115,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { + Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -121,8 +124,7 @@ public class TelemetryMonitor { UAVObject obj = queue.remove(0); if(obj == null) { - Log.e(TAG, "Got null object forom transaction queue"); - return; + throw new Error("Got null object forom transaction queue"); } Log.d(TAG, "Retrieving object: " + obj.getName()) ; @@ -130,6 +132,7 @@ public class TelemetryMonitor { obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -146,11 +149,16 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted"); + Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; + if(!success) { + Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); + return; + } + // Process next object if telemetry is still available if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -184,6 +192,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats + Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -221,9 +230,9 @@ public class TelemetryMonitor { return; } UAVObjectField statusField = gcsStatsObj.getField("Status"); - String oldStatus = (String) statusField.getValue(); + String oldStatus = new String((String) statusField.getValue()); - System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -236,7 +245,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - System.out.println("Connected" + statusField.toString()); + Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -251,31 +260,31 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) - System.out.println("GCS Status changed"); + if(gcsStatusChanged) { + Log.d(TAG,"GCS Status changed"); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; - if ( gcsStatusChanged || - ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) + if ( !gcsConnected || !flightConnected ) { - System.out.println("Sending gcs status\n\n\n"); + Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { + Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot established"); - //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { + Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot lost"); - //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index b74df9218..ba3bf1ae3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -102,6 +102,18 @@ public abstract class UAVObject { } } + private CallbackListener updateRequestedListeners = new CallbackListener(this); + public void addUpdateRequestedObserver(Observer o) { + synchronized(updateRequestedListeners) { + updateRequestedListeners.addObserver(o); + } + } + void updateRequested() { + synchronized(updateRequestedListeners) { + updateRequestedListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 8d792bb39..de2059e90 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -358,7 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } - obj.updated(); + //obj.updated(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 825f9d9fe..33daefab7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -9,49 +9,66 @@ import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.Observable; -public class UAVTalk extends Observable{ +import android.util.Log; + +public class UAVTalk extends Observable { + + static final String TAG = "UAVTalk"; + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; private Thread inputProcessingThread = null; + /** * A reference to the thread for processing the incoming stream + * * @return */ public Thread getInputProcessThread() { - if(inputProcessingThread == null) + if (inputProcessingThread == null) inputProcessingThread = new Thread() { - public void run() { - processInputStream(); - } - }; + public void run() { + processInputStream(); + } + }; return inputProcessingThread; } - + /** * Constants */ private static final int SYNC_VAL = 0x3C; - private static final short crc_table[] = { - 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, - 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, - 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, - 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, - 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, - 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, - 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, - 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, - 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, - 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, - 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, - 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, - 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, - 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, - 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, - 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 - }; + private static final short crc_table[] = { 0x00, 0x07, 0x0e, 0x09, 0x1c, + 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, + 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, + 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, 0x90, + 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, + 0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, + 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, + 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, + 0x94, 0x9d, 0x9a, 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, + 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, + 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, + 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, + 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, 0xf9, 0xfe, 0xf7, 0xf0, + 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, + 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, + 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10, 0x05, + 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, + 0x7f, 0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, + 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, + 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, + 0x8a, 0x8d, 0x84, 0x83, 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, + 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 }; - enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + enum RxStateType { + STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS + }; static final int TYPE_MASK = 0xFC; static final int TYPE_VER = 0x20; @@ -60,17 +77,21 @@ public class UAVTalk extends Observable{ static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); static final int TYPE_ACK = (TYPE_VER | 0x03); - static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) - static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), + // object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), + // object ID (4), instance ID(2, + // not used in single objects) static final int CHECKSUM_LENGTH = 1; static final int MAX_PAYLOAD_LENGTH = 256; - static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); static final int ALL_INSTANCES = 0xFFFF; - static final int TX_BUFFER_SIZE = 2*1024; + static final int TX_BUFFER_SIZE = 2 * 1024; /** * Private data @@ -93,12 +114,12 @@ public class UAVTalk extends Observable{ int rxCSPacket, rxCS; int rxCount; int packetSize; - RxStateType rxState; + RxStateType rxState; ComStats stats = new ComStats(); /** * Comm stats - */ + */ public class ComStats { public int txBytes = 0; public int rxBytes = 0; @@ -113,8 +134,8 @@ public class UAVTalk extends Observable{ /** * Constructor */ - public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) - { + public UAVTalk(InputStream inStream, OutputStream outStream, + UAVObjectManager objMngr) { this.objMngr = objMngr; this.inStream = inStream; this.outStream = outStream; @@ -122,7 +143,7 @@ public class UAVTalk extends Observable{ rxState = RxStateType.STATE_SYNC; rxPacketLength = 0; - //mutex = new QMutex(QMutex::Recursive); + // mutex = new QMutex(QMutex::Recursive); respObj = null; resetStats(); @@ -131,88 +152,80 @@ public class UAVTalk extends Observable{ rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); rxBuffer.order(ByteOrder.LITTLE_ENDIAN); - // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, + // SLOT(processInputStream())); } /** * Reset the statistics counters */ - public void resetStats() - { - //QMutexLocker locker(mutex); + public void resetStats() { + // QMutexLocker locker(mutex); stats = new ComStats(); } /** * Get the statistics counters */ - public ComStats getStats() - { - //QMutexLocker locker(mutex); + public ComStats getStats() { + // QMutexLocker locker(mutex); return stats; } /** * Called each time there are data in the input buffer */ - public void processInputStream() - { + public void processInputStream() { int val; - - while (true) - { + + while (true) { try { - //inStream.wait(); + // inStream.wait(); val = inStream.read(); - } /*catch (InterruptedException e) { - // TODO Auto-generated catch block - System.out.println("Connection was aborted\n"); - e.printStackTrace(); - break; - }*/ catch (IOException e) { + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { // TODO Auto-generated catch block System.out.println("Error reading from stream\n"); e.printStackTrace(); break; } - if(val == -1) { - System.out.println("End of stream, terminating processInputStream thread"); + if (val == -1) { + System.out + .println("End of stream, terminating processInputStream thread"); break; } - - //System.out.println("Received byte " + val + " in state + " + rxState); + + // System.out.println("Received byte " + val + " in state + " + + // rxState); processInputByte(val); } } /** - * Request an update for the specified object, on success the object data would have been - * updated by the GCS. - * \param[in] obj Object to update + * Request an update for the specified object, on success the object data + * would have been updated by the GCS. \param[in] obj Object to update * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObjectRequest(UAVObject obj, boolean allInstances) - { - //QMutexLocker locker(mutex); + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) { + // QMutexLocker locker(mutex); return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); } /** - * Send the specified object through the telemetry link. - * \param[in] obj Object to send - * \param[in] acked Selects if an ack is required - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Send the specified object through the telemetry link. \param[in] obj + * Object to send \param[in] acked Selects if an ack is required \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) - { - if (acked) - { + public synchronized boolean sendObject(UAVObject obj, boolean acked, + boolean allInstances) { + if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); - } - else - { + } else { return objectTransaction(obj, TYPE_OBJ, allInstances); } } @@ -220,64 +233,49 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public synchronized void cancelTransaction() - { + public synchronized void cancelTransaction() { respObj = null; } /** - * Execute the requested transaction on an object. - * \param[in] obj Object - * \param[in] type Transaction type - * TYPE_OBJ: send object, - * TYPE_OBJ_REQ: request object update - * TYPE_OBJ_ACK: send object with an ack - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Execute the requested transaction on an object. \param[in] obj Object + * \param[in] type Transaction type TYPE_OBJ: send object, TYPE_OBJ_REQ: + * request object update TYPE_OBJ_ACK: send object with an ack \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) - { + public boolean objectTransaction(UAVObject obj, int type, + boolean allInstances) { // Send object depending on if a response is needed - if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) - { - if ( transmitObject(obj, type, allInstances) ) - { + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) { + if (transmitObject(obj, type, allInstances)) { respObj = obj; - respAllInstances = allInstances; + respAllInstances = allInstances; return true; - } - else - { + } else { return false; } - } - else if (type == TYPE_OBJ) - { + } else if (type == TYPE_OBJ) { return transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { return false; } } /** - * Process an byte from the telemetry stream. - * \param[in] rxbyte Received byte - * \return Success (true), Failure (false) + * Process an byte from the telemetry stream. \param[in] rxbyte Received + * byte \return Success (true), Failure (false) */ - public synchronized boolean processInputByte(int rxbyte) - { - assert(objMngr != null); + public synchronized boolean processInputByte(int rxbyte) { + assert (objMngr != null); // Update stats stats.rxBytes++; - rxPacketLength++; // update packet byte count + rxPacketLength++; // update packet byte count // Receive state machine - switch (rxState) - { + switch (rxState) { case STATE_SYNC: if (rxbyte != SYNC_VAL) @@ -296,8 +294,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if ((rxbyte & TYPE_MASK) != TYPE_VER) - { + if ((rxbyte & TYPE_MASK) != TYPE_VER) { rxState = RxStateType.STATE_SYNC; break; } @@ -315,8 +312,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if (rxCount == 0) - { + if (rxCount == 0) { packetSize += rxbyte; rxCount++; break; @@ -324,10 +320,12 @@ public class UAVTalk extends Observable{ packetSize += (rxbyte << 8) & 0xff00; - if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) - { // incorrect packet size + if (packetSize < MIN_HEADER_LENGTH + || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) { // incorrect + // packet + // size rxState = RxStateType.STATE_SYNC; - break; + break; } rxCount = 0; @@ -348,8 +346,7 @@ public class UAVTalk extends Observable{ rxObjId = rxTmpBuffer.getInt(0); { UAVObject rxObj = objMngr.getObject(rxObjId); - if (rxObj == null) - { + if (rxObj == null) { stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -361,38 +358,38 @@ public class UAVTalk extends Observable{ else rxLength = rxObj.getNumBytes(); - // Check length and determine next state - if (rxLength >= MAX_PAYLOAD_LENGTH) - { - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check the lengths match - if ((rxPacketLength + rxLength) != packetSize) - { // packet error - mismatched packet size - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) { // packet error + // - + // mismatched + // packet + // size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check if this is a single instance object (i.e. if the instance ID field is coming next) - if (rxObj.isSingleInstance()) - { - // If there is a payload get it, otherwise receive checksum - if (rxLength > 0) - rxState = RxStateType.STATE_DATA; - else - rxState = RxStateType.STATE_CS; - rxInstId = 0; - rxCount = 0; - } + // Check if this is a single instance object (i.e. if the + // instance ID field is coming next) + if (rxObj.isSingleInstance()) { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; else - { - rxState = RxStateType.STATE_INSTID; - rxCount = 0; - } + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } else { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } } break; @@ -419,7 +416,7 @@ public class UAVTalk extends Observable{ break; case STATE_DATA: - + // Update CRC rxCS = updateCRC(rxCS, rxbyte); @@ -436,15 +433,15 @@ public class UAVTalk extends Observable{ // The CRC byte rxCSPacket = rxbyte; - if (rxCS != rxCSPacket) - { // packet error - faulty CRC + if (rxCS != rxCSPacket) { // packet error - faulty CRC stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } - if (rxPacketLength != (packetSize + 1)) - { // packet error - mismatched packet size + if (rxPacketLength != (packetSize + 1)) { // packet error - + // mismatched packet + // size stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -468,103 +465,84 @@ public class UAVTalk extends Observable{ } /** - * Receive an object. This function process objects received through the telemetry stream. - * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) - * \param[in] obj Handle of the received object - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] data Data buffer - * \param[in] length Buffer length - * \return Success (true), Failure (false) + * Receive an object. This function process objects received through the + * telemetry stream. \param[in] type Type of received message (TYPE_OBJ, + * TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) \param[in] obj Handle of the + * received object \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES + * for all instances. \param[in] data Data buffer \param[in] length Buffer + * length \return Success (true), Failure (false) */ - public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); - + public boolean receiveObject(int type, int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); + UAVObject obj = null; boolean error = false; - boolean allInstances = (instId == ALL_INSTANCES? true : false); + boolean allInstances = (instId == ALL_INSTANCES ? true : false); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages - if (!allInstances) - { - System.out.println("Received object: " + objMngr.getObject(objId).getName()); + if (!allInstances) { + if (DEBUG) Log.d(TAG,"Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending - if ( obj != null ) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages - if (!allInstances) - { -// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received object ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK - if ( obj != null ) - { + if (obj != null) { transmitObject(obj, TYPE_ACK, false); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_REQ: - // Get object, if all instances are requested get instance 0 of the object -// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); - if (allInstances) - { + // Get object, if all instances are requested get instance 0 of the + // object + // System.out.println("Received object request: " + objId + " " + + // objMngr.getObject(objId).getName()); + if (allInstances) { obj = objMngr.getObject(objId); - } - else - { + } else { obj = objMngr.getObject(objId, instId); } // If object was found transmit it - if (obj != null) - { + if (obj != null) { transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { error = true; } break; case TYPE_ACK: // All instances, not allowed for ACK messages - if (!allInstances) - { -// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending - if (obj != null) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } } @@ -577,23 +555,20 @@ public class UAVTalk extends Observable{ } /** - * Update the data of an object from a byte array (unpack). - * If the object instance could not be found in the list, then a - * new one is created. + * Update the data of an object from a byte array (unpack). If the object + * instance could not be found in the list, then a new one is created. */ - public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); + public synchronized UAVObject updateObject(int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); // Get object UAVObject obj = objMngr.getObject(objId, instId); // If the instance does not exist create it - if (obj == null) - { + if (obj == null) { // Get the object type UAVObject tobj = objMngr.getObject(objId); - if (tobj == null) - { + if (tobj == null) { return null; } // Make sure this is a data object @@ -604,26 +579,26 @@ public class UAVTalk extends Observable{ // Failed to cast to a data object return null; } - + // Create a new instance, unpack and register UAVDataObject instobj = dobj.clone(instId); try { - if ( !objMngr.registerObject(instobj) ) - { + if (!objMngr.registerObject(instobj)) { return null; } } catch (Exception e) { // TODO Auto-generated catch block e.printStackTrace(); } -// System.out.println("Unpacking new object"); + // System.out.println("Unpacking new object"); + if (DEBUG) Log.d(TAG, "Unpacking new object"); instobj.unpack(data); return instobj; - } - else - { + } else { // Unpack data into object instance -// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); + // System.out.println("Unpacking existing object: " + + // data.position() + " / " + data.capacity() ); + if (DEBUG) Log.d(TAG, "Unpacking existing object: " + obj.getName()); obj.unpack(data); return obj; } @@ -632,10 +607,9 @@ public class UAVTalk extends Observable{ /** * Check if a transaction is pending and if yes complete it. */ - public void updateAck(UAVObject obj) - { - if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) - { + synchronized void updateAck(UAVObject obj) { + if (respObj != null && respObj.getObjID() == obj.getObjID() + && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; setChanged(); notifyObservers(obj); @@ -643,111 +617,88 @@ public class UAVTalk extends Observable{ } /** - * Send an object through the telemetry link. - * \param[in] obj Object to send - * \param[in] type Transaction type - * \param[in] allInstances True is all instances of the object are to be sent - * \return Success (true), Failure (false) + * Send an object through the telemetry link. + * @param[in] obj Object to send + * @param[in] type Transaction type + * @param[in] allInstances True is all instances of the object are to be sent + * @return Success (true), Failure (false) */ - public boolean transmitObject(UAVObject obj, int type, boolean allInstances) - { - // If all instances are requested on a single instance object it is an error - if (allInstances && obj.isSingleInstance()) - { + public synchronized boolean transmitObject(UAVObject obj, int type, boolean allInstances) { + // If all instances are requested on a single instance object it is an + // error + if (allInstances && obj.isSingleInstance()) { allInstances = false; } // Process message type - if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) - { - if (allInstances) - { + if (type == TYPE_OBJ || type == TYPE_OBJ_ACK) { + if (allInstances) { // Get number of instances int numInst = objMngr.getNumInstances(obj.getObjID()); // Send all instances - for (int instId = 0; instId < numInst; ++instId) - { + for (int instId = 0; instId < numInst; ++instId) { UAVObject inst = objMngr.getObject(obj.getObjID(), instId); transmitSingleObject(inst, type, false); } return true; - } - else - { + } else { return transmitSingleObject(obj, type, false); } - } - else if (type == TYPE_OBJ_REQ) - { + } else if (type == TYPE_OBJ_REQ) { return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); - } - else if (type == TYPE_ACK) - { - if (!allInstances) - { + } else if (type == TYPE_ACK) { + if (!allInstances) { return transmitSingleObject(obj, TYPE_ACK, false); - } - else - { + } else { return false; } - } - else - { + } else { return false; } } - /** - * Send an object through the telemetry link. - * \param[in] obj Object handle to send - * \param[in] type Transaction type - * \return Success (true), Failure (false) + * Send an object through the telemetry link. \param[in] obj Object handle + * to send \param[in] type Transaction type \return Success (true), Failure + * (false) */ - public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) - { + public synchronized boolean transmitSingleObject(UAVObject obj, int type, + boolean allInstances) { int length; int dataOffset; int objId; int instId; int allInstId = ALL_INSTANCES; - - assert(objMngr != null && outStream != null); - + + assert (objMngr != null && outStream != null); + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); bbuf.order(ByteOrder.LITTLE_ENDIAN); // Determine data length - if (type == TYPE_OBJ_REQ || type == TYPE_ACK) - { + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) { length = 0; - } - else - { + } else { length = obj.getNumBytes(); } - + // Setup type and object id fields bbuf.put((byte) (SYNC_VAL & 0xff)); bbuf.put((byte) (type & 0xff)); - bbuf.putShort((short) (length + - 2 /* SYNC, Type */ + - 2 /* Size */ + - 4 /* ObjID */ + - (obj.isSingleInstance() ? 0 : 2) )); + bbuf + .putShort((short) (length + 2 /* SYNC, Type */+ 2 /* Size */+ 4 /* ObjID */+ (obj + .isSingleInstance() ? 0 : 2))); bbuf.putInt(obj.getObjID()); - + // Setup instance ID if one is required - if ( !obj.isSingleInstance() ) - { + if (!obj.isSingleInstance()) { // Check if all instances are requested if (allInstances) bbuf.putShort((short) (allInstId & 0xffff)); else bbuf.putShort((short) (obj.getInstID() & 0xffff)); } - + // Check length if (length >= MAX_PAYLOAD_LENGTH) return false; @@ -755,7 +706,7 @@ public class UAVTalk extends Observable{ // Copy data (if any) if (length > 0) try { - if ( obj.pack(bbuf) == 0) + if (obj.pack(bbuf) == 0) return false; } catch (Exception e) { // TODO Auto-generated catch block @@ -769,26 +720,28 @@ public class UAVTalk extends Observable{ try { int packlen = bbuf.position(); bbuf.position(0); - byte [] dst = new byte[packlen]; - bbuf.get(dst,0,packlen); + byte[] dst = new byte[packlen]; + bbuf.get(dst, 0, packlen); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); return false; } - -// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE -// // Send buffer, check that the transmit backlog does not grow above limit -// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) -// { -// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); -// } -// else -// { -// ++stats.txErrors; -// return false; -// } + + // //TODO: Need to use a different outStream type and check that the + // backlog isn't more than TX_BUFFER_SIZE + // // Send buffer, check that the transmit backlog does not grow above + // limit + // if ( io->bytesToWrite() < TX_BUFFER_SIZE ) + // { + // io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); + // } + // else + // { + // ++stats.txErrors; + // return false; + // } // Update stats ++stats.txObjects; @@ -801,33 +754,23 @@ public class UAVTalk extends Observable{ /** * Update the crc value with new data. - * - * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ - * using the configuration: - * Width = 8 - * Poly = 0x07 - * XorIn = 0x00 - * ReflectIn = False - * XorOut = 0x00 - * ReflectOut = False - * Algorithm = table-driven - * - * \param crc The current crc value. - * \param data Pointer to a buffer of \a data_len bytes. - * \param length Number of bytes in the \a data buffer. - * \return The updated crc value. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ using the + * configuration: Width = 8 Poly = 0x07 XorIn = 0x00 ReflectIn = False + * XorOut = 0x00 ReflectOut = False Algorithm = table-driven + * + * \param crc The current crc value. \param data Pointer to a buffer of \a + * data_len bytes. \param length Number of bytes in the \a data buffer. + * \return The updated crc value. */ - int updateCRC(int crc, int data) - { + int updateCRC(int crc, int data) { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data, int length) - { + + int updateCRC(int crc, byte[] data, int length) { for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); - return crc; + return crc; } - - } From 38213de9aa40450a745e4bec8441057972c95e3a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:57:18 -0500 Subject: [PATCH 225/508] Make the UAVTalk object process one byte per call so it can be embedded in another loop. Also clean up some warnings. --- .../src/org/openpilot/uavtalk/UAVTalk.java | 59 +++++++++---------- 1 file changed, 28 insertions(+), 31 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 33daefab7..8671cdef9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -1,7 +1,5 @@ package org.openpilot.uavtalk; -import java.io.ByteArrayInputStream; -import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.OutputStream; @@ -30,7 +28,10 @@ public class UAVTalk extends Observable { inputProcessingThread = new Thread() { public void run() { - processInputStream(); + while(true) { + if( !processInputStream() ) + break; + } } }; return inputProcessingThread; @@ -173,37 +174,36 @@ public class UAVTalk extends Observable { } /** - * Called each time there are data in the input buffer + * Process any data in the queue */ - public void processInputStream() { + public boolean processInputStream() { int val; - while (true) { - try { - // inStream.wait(); - val = inStream.read(); - } /* - * catch (InterruptedException e) { // TODO Auto-generated catch - * block System.out.println("Connection was aborted\n"); - * e.printStackTrace(); break; } - */catch (IOException e) { - // TODO Auto-generated catch block - System.out.println("Error reading from stream\n"); - e.printStackTrace(); - break; - } - if (val == -1) { - System.out - .println("End of stream, terminating processInputStream thread"); - break; - } + try { + // inStream.wait(); + val = inStream.read(); + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + return false; + } + if (val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + return false; + } - // System.out.println("Received byte " + val + " in state + " + - // rxState); - processInputByte(val); - } + // System.out.println("Received byte " + val + " in state + " + + // rxState); + processInputByte(val); + return true; } + /** * Request an update for the specified object, on success the object data * would have been updated by the GCS. \param[in] obj Object to update @@ -665,9 +665,6 @@ public class UAVTalk extends Observable { public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; - int dataOffset; - int objId; - int instId; int allInstId = ALL_INSTANCES; assert (objMngr != null && outStream != null); From 6edafd2c5f63d678d3346a1baaf2a6f8a1cf7e8f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:58:55 -0500 Subject: [PATCH 226/508] Create a UAVTalk service that is called from the object browser --- androidgcs/AndroidManifest.xml | 1 + .../androidgcs/BluetoothUAVTalk.java | 146 ++++++++++++++++++ .../androidgcs/OPTelemetryService.java | 88 +++++++++++ .../openpilot/androidgcs/ObjectBrowser.java | 97 +----------- 4 files changed, 238 insertions(+), 94 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 8b3a9e4b3..6c89f2632 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,5 +18,6 @@ + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java new file mode 100644 index 000000000..b240f3adc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -0,0 +1,146 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.BroadcastReceiver; +import android.content.Context; +import android.content.Intent; +import android.util.Log; + +public class BluetoothUAVTalk { + private final String TAG = "BluetoothUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String DEVICE_NAME = "RN42-222D"; + private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + + private BluetoothAdapter mBluetoothAdapter; + private BluetoothSocket socket; + private BluetoothDevice device; + private UAVTalk uavTalk; + private boolean connected; + + public BluetoothUAVTalk(Context caller, String deviceName) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + + connected = false; + device = null; + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.e(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + // Enable bluetooth if it isn't already + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + caller.sendOrderedBroadcast(enableBtIntent, "android.permission.BLUETOOTH_ADMIN", new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.e(TAG,"Received " + context + intent); + //TODO: some logic here to see if it worked + queryDevices(); + } + }, null, Activity.RESULT_OK, null, null); + } else { + queryDevices(); + } + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !getFoundDevice() ) + return false; + if( !openTelemetryBluetooth(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public boolean getFoundDevice() { + return (device != null); + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + private void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + this.device = device; + return; + } + } + } + + } + + private boolean openTelemetryBluetooth(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + socket = null; + connected = false; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + return false; + //e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java new file mode 100644 index 000000000..2994be6d2 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -0,0 +1,88 @@ +package org.openpilot.androidgcs; + +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.app.Service; +import android.content.Intent; +import android.os.IBinder; +import android.os.Looper; +import android.util.Log; + +public class OPTelemetryService extends Service { + private final String TAG = "OPTElemetryService"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + @Override + public IBinder onBind(Intent arg0) { + return null; + } + + @Override + public void onCreate() { + super.onCreate(); + + if (DEBUG) Log.d(TAG, "Telemetry Service started"); + + Thread telemetryThread = new Thread(telemetryRunnable); + telemetryThread.start(); + } + + @Override + public void onDestroy() { + super.onDestroy(); + } + + private final Runnable telemetryRunnable = new Runnable() { + + public void run() { + Looper.prepare(); + + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + while(true) { + if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); + if(! bt.getConnected() ) + bt.connect(objMngr); + else + break; + Looper.loop(); + } + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); + + uavTalk = bt.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while(true) { + if( !uavTalk.processInputStream() ) + break; + Looper.loop(); + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + + public UAVObjectManager getObjMngr() { return objMngr; }; + public UAVTalk getUavTalk() { return uavTalk; }; + public Telemetry getTelemetry() { return tel; }; + public TelemetryMonitor getTelemetryMonitor() { return mon; }; + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a8c58d58d..6bb217930 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -69,26 +69,12 @@ public class ObjectBrowser extends Activity { Log.d(TAG, "Launching Object Browser"); - connected = false; + Log.d(TAG, "Start OP Telemetry Service"); + startService( new Intent( this, OPTelemetryService.class ) ); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); - if (mBluetoothAdapter == null) { - // Device does not support Bluetooth - Log.e(TAG, "Device does not support Bluetooth"); - return; - } - - if (!mBluetoothAdapter.isEnabled()) { - Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); - startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); - } else { - queryDevices(); - } - - UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -116,84 +102,7 @@ public class ObjectBrowser extends Activity { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } - }); - - + }); } - @Override - public void onActivityResult(int requestCode, int resultCode, Intent data) { - if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - //Log.d(TAG, "Bluetooth started succesfully"); - queryDevices(); - } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { - //Log.d(TAG, "Bluetooth could not be started"); - } - - } - - public void queryDevices() { - Log.d(TAG, "Searching for devices"); - Set pairedDevices = mBluetoothAdapter.getBondedDevices(); - // If there are paired devices - if (pairedDevices.size() > 0) { - // Loop through paired devices - for (BluetoothDevice device : pairedDevices) { - // Add the name and address to an array adapter to show in a ListView - //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); - Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { - openTelmetryBluetooth(device); - openTelmetryBluetooth(device); - } - } - } - - } - - private void openTelmetryBluetooth(BluetoothDevice device) { - Log.d(TAG, "Opening conncetion to " + device.getName()); - socket = null; - connected = false; - try { - socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); - } catch (IOException e) { - Log.e(TAG,"Unable to create Rfcomm socket"); - //e.printStackTrace(); - } - - mBluetoothAdapter.cancelDiscovery(); - - try { - socket.connect(); - } - catch (IOException e) { - Log.e(TAG,"Unable to connect to requested device", e); - try { - socket.close(); - } catch (IOException e2) { - //Log.e(TAG, "unable to close() socket during connection failure", e2); - } - return; - } - - connected = true; - - try { - uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); - } catch (IOException e) { - Log.e(TAG,"Error starting UAVTalk"); - // TODO Auto-generated catch block - //e.printStackTrace(); - return; - } - - Thread inputStream = uavTalk.getInputProcessThread(); - inputStream.start(); - - Telemetry tel = new Telemetry(uavTalk, objMngr); - TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); - - } } From 5e2c2a0ec3868f5e3d61f8c5e927cf93de99fbe8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 10:09:35 -0500 Subject: [PATCH 227/508] Clean up the logging somewhat --- .../androidgcs/OPTelemetryService.java | 62 ++++++++++++++++--- .../openpilot/uavtalk/TelemetryMonitor.java | 31 +++++----- flight/Revolution/Makefile.osx | 5 +- 3 files changed, 72 insertions(+), 26 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 2994be6d2..5a48bbc05 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -6,8 +6,14 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import android.app.Notification; +import android.app.NotificationManager; +import android.app.PendingIntent; import android.app.Service; +import android.content.Context; import android.content.Intent; +import android.net.Uri; +import android.os.Handler; import android.os.IBinder; import android.os.Looper; import android.util.Log; @@ -18,10 +24,16 @@ public class OPTelemetryService extends Service { public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; + final int DISCONNECT_MESSAGE = 0; + final int CONNECT_MESSAGE = 1; + final int CONNECT_FAILED_MESSAGE = 2; + private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; private TelemetryMonitor mon; + + private Handler handler; @Override public IBinder onBind(Intent arg0) { @@ -46,22 +58,38 @@ public class OPTelemetryService extends Service { private final Runnable telemetryRunnable = new Runnable() { public void run() { - Looper.prepare(); - if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - + + postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); - while(true) { + for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - if(! bt.getConnected() ) - bt.connect(objMngr); - else + + bt.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( bt.getConnected() ) break; - Looper.loop(); + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } } + if( ! bt.getConnected() ) { + postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); + return; + } + + postNotification(CONNECT_MESSAGE, "Connected to UAV port"); if (DEBUG) Log.d(TAG, "Connected via bluetooth"); @@ -73,13 +101,29 @@ public class OPTelemetryService extends Service { while(true) { if( !uavTalk.processInputStream() ) break; - Looper.loop(); } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } }; + void postNotification(int id, String message) { + String ns = Context.NOTIFICATION_SERVICE; + NotificationManager mNManager = (NotificationManager) getSystemService(ns); + final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); + + Context context = getApplicationContext(); + CharSequence contentTitle = "OpenPilot"; + CharSequence contentText = message; + Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); + PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); + + msg.setLatestEventInfo(context, contentTitle, contentText, intent); + + mNManager.notify(id, msg); + } + public UAVObjectManager getObjMngr() { return objMngr; }; public UAVTalk getUavTalk() { return uavTalk; }; public Telemetry getTelemetry() { return tel; }; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index a5885e7bc..9b4474d8e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -16,7 +16,10 @@ import android.util.Log; public class TelemetryMonitor { private static final String TAG = "TelemetryMonitor"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + static final int STATS_UPDATE_PERIOD_MS = 4000; static final int STATS_CONNECT_PERIOD_MS = 1000; static final int CONNECTION_TIMEOUT_MS = 8000; @@ -57,7 +60,7 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { - Log.d(TAG, "Start retrieving objects"); + if (DEBUG) Log.d(TAG, "Start retrieving objects"); // Clear object queue queue.clear(); @@ -115,7 +118,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { - Log.d(TAG, "All objects retrieved: Connected Successfully"); + if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -127,12 +130,12 @@ public class TelemetryMonitor { throw new Error("Got null object forom transaction queue"); } - Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if (DEBUG) Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; - Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); + if (DEBUG) Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -149,7 +152,7 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted. Status: " + success); + if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; @@ -192,7 +195,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats - Log.d(TAG, "processStatsUpdates()"); + if (DEBUG) Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -232,7 +235,7 @@ public class TelemetryMonitor { UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = new String((String) statusField.getValue()); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -245,7 +248,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - Log.d(TAG,"Connected" + statusField.toString()); + if (DEBUG) Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -260,30 +263,26 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) { - Log.d(TAG,"GCS Status changed"); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); - } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; if ( !gcsConnected || !flightConnected ) { - Log.d(TAG,"Sending gcs status"); + if (DEBUG) Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { - Log.d(TAG,"Connection with the autopilot established"); + if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { - Log.d(TAG,"Trying to connect to the autopilot"); + if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); //emit disconnected(); } diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index 91bddb9a5..e2c8ea694 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -41,7 +41,7 @@ USE_BOOTLOADER ?= NO CODE_SOURCERY ?= NO # Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= "" +TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- # Remove command is different for Code Sourcery on Windows REMOVE_CMD ?= rm @@ -320,6 +320,9 @@ CFLAGS += -mtune=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + CFLAGS += -fomit-frame-pointer ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices From 529b450f1dccc2d120d98b9fd8977b7e319689ed Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 19:58:57 -0500 Subject: [PATCH 228/508] Common Activity class that binds to the Telemetry service --- .../androidgcs/ObjectManagerActivity.java | 97 +++++++++++++++++++ 1 file changed, 97 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java new file mode 100644 index 000000000..9f57796dc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -0,0 +1,97 @@ +package org.openpilot.androidgcs; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVObjectManager; + +import android.app.Activity; +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; + +public abstract class ObjectManagerActivity extends Activity { + + private final String TAG = "ObjectManagerActivity"; + private static int LOGLEVEL = 2; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + void onOPConnected() { + + } + + void onOPDisconnected() { + + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + binder = (LocalBinder) service; + binder.openFakeConnection(); + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + mConnected = false; + objMngr = null; + } + }; +} From 515a4c4fd1c6cc3a033c137f806d310ab7bdfda4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 20:00:12 -0500 Subject: [PATCH 229/508] Start of a widget for monitoring telemetry status --- androidgcs/AndroidManifest.xml | 43 +++++++++++++------ androidgcs/res/layout/telemetry_widget.xml | 7 +++ .../openpilot/androidgcs/TelemetryWidget.java | 31 +++++++++++++ 3 files changed, 67 insertions(+), 14 deletions(-) create mode 100644 androidgcs/res/layout/telemetry_widget.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 6c89f2632..9a3d1dd25 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -1,23 +1,38 @@ - + package="org.openpilot.androidgcs" android:versionCode="1" + android:versionName="1.0"> + - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - + \ No newline at end of file diff --git a/androidgcs/res/layout/telemetry_widget.xml b/androidgcs/res/layout/telemetry_widget.xml new file mode 100644 index 000000000..6af378104 --- /dev/null +++ b/androidgcs/res/layout/telemetry_widget.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java new file mode 100644 index 000000000..90ab80899 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -0,0 +1,31 @@ +package org.openpilot.androidgcs; + +import android.appwidget.AppWidgetManager; +import android.appwidget.AppWidgetProvider; +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.widget.RemoteViews; + +public class TelemetryWidget extends AppWidgetProvider { + + private static boolean connected = false; + + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { + final int N = appWidgetIds.length; + + // Perform this loop procedure for each App Widget that belongs to this provider + for (int i=0; i Date: Sat, 19 Mar 2011 20:01:01 -0500 Subject: [PATCH 230/508] Get rid of lots of warnings --- .../androidgcs/OPTelemetryService.java | 211 ++++++++++++++---- .../openpilot/androidgcs/ObjectBrowser.java | 83 ++----- .../openpilot/androidgcs/TelemetryWidget.java | 4 - .../src/org/openpilot/uavtalk/Telemetry.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 11 +- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 11 +- 7 files changed, 194 insertions(+), 129 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5a48bbc05..557c3b256 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -2,6 +2,7 @@ package org.openpilot.androidgcs; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -13,69 +14,192 @@ import android.app.Service; import android.content.Context; import android.content.Intent; import android.net.Uri; +import android.os.Binder; import android.os.Handler; +import android.os.HandlerThread; import android.os.IBinder; import android.os.Looper; +import android.os.Message; +import android.os.Process; import android.util.Log; +import android.widget.Toast; public class OPTelemetryService extends Service { + + // Logging settings private final String TAG = "OPTElemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - final int DISCONNECT_MESSAGE = 0; - final int CONNECT_MESSAGE = 1; - final int CONNECT_FAILED_MESSAGE = 2; - - private UAVObjectManager objMngr; - private UAVTalk uavTalk; - private Telemetry tel; - private TelemetryMonitor mon; - - private Handler handler; + // Intent category + public final static String INTENT_CATEGORY_GCS = "org.openpilot.intent.category.GCS"; - @Override - public IBinder onBind(Intent arg0) { - return null; - } + // Intent actions + public final static String INTENT_ACTION_CONNECTED = "org.openpilot.intent.action.CONNECTED"; + public final static String INTENT_ACTION_DISCONNECTED = "org.openpilot.intent.action.DISCONNECTED"; + + // Variables for local message handler thread + private Looper mServiceLooper; + private ServiceHandler mServiceHandler; + + // Message ids + final int MSG_START = 0; + final int MSG_CONNECT_BT = 1; + final int MSG_CONNECT_FAKE = 2; + final int MSG_TOAST = 100; + + private Thread activeTelem; + + private final IBinder mBinder = new LocalBinder(); + + private final class ServiceHandler extends Handler { + public ServiceHandler(Looper looper) { + super(looper); + } + @Override + public void handleMessage(Message msg) { + switch(msg.arg1) { + case MSG_START: + Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); + System.out.println("HERE"); + stopSelf(msg.arg2); + case MSG_CONNECT_BT: + activeTelem = new BTTelemetryThread(); + activeTelem.start(); + break; + case MSG_CONNECT_FAKE: + activeTelem = new FakeTelemetryThread(); + activeTelem.start(); + break; + case MSG_TOAST: + Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); + break; + default: + System.out.println(msg.toString()); + throw new Error("Invalid message"); + } + } + }; @Override public void onCreate() { - super.onCreate(); - - if (DEBUG) Log.d(TAG, "Telemetry Service started"); + // Low priority thread for message handling with service + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", + Process.THREAD_PRIORITY_BACKGROUND); + thread.start(); - Thread telemetryThread = new Thread(telemetryRunnable); - telemetryThread.start(); - } + // Get the HandlerThread's Looper and use it for our Handler + mServiceLooper = thread.getLooper(); + mServiceHandler = new ServiceHandler(mServiceLooper); + } + + @Override + public int onStartCommand(Intent intent, int flags, int startId) { + Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); + + System.out.println("Start"); + // For each start request, send a message to start a job and deliver the + // start ID so we know which request we're stopping when we finish the job + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_START; + msg.arg2 = startId; + mServiceHandler.sendMessage(msg); + + // If we get killed, after returning from here, restart + return START_STICKY; + } + + @Override + public IBinder onBind(Intent intent) { + return mBinder; + } @Override public void onDestroy() { - super.onDestroy(); + Toast.makeText(this, "Telemetry service done", Toast.LENGTH_SHORT).show(); } + + public class LocalBinder extends Binder { + public TelemTask getTelemTask(int id) { + return (TelemTask) activeTelem; + } + public void openFakeConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_FAKE; + mServiceHandler.sendMessage(msg); + } + }; - private final Runnable telemetryRunnable = new Runnable() { + public void toastMessage(String msgText) { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_TOAST; + msg.obj = msgText; + mServiceHandler.sendMessage(msg); + } + + public interface TelemTask { + public UAVObjectManager getObjectManager(); + }; + + // Fake class for testing, simply emits periodic updates on + private class FakeTelemetryThread extends Thread implements TelemTask { + private UAVObjectManager objMngr; + public UAVObjectManager getObjectManager() { return objMngr; }; + + FakeTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + System.out.println("Runnin fake thread"); + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + + //toastMessage("Started fake telemetry thread"); + UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + while(true) { + systemStats.updated(); + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + break; + } + } + } + } + private class BTTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + //private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + BTTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } public void run() { if (DEBUG) Log.d(TAG, "Telemetry Thread started"); Looper.prepare(); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - - postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - + bt.connect(objMngr); - + if (DEBUG) Log.d(TAG, "Done attempting connection"); if( bt.getConnected() ) break; - + try { Thread.sleep(1000); } catch (InterruptedException e) { @@ -85,17 +209,15 @@ public class OPTelemetryService extends Service { } } if( ! bt.getConnected() ) { - postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); return; } - - postNotification(CONNECT_MESSAGE, "Connected to UAV port"); - + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); - + uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - mon = new TelemetryMonitor(objMngr,tel); + new TelemetryMonitor(objMngr,tel); if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); while(true) { @@ -103,30 +225,23 @@ public class OPTelemetryService extends Service { break; } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); - postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } - + }; - + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); - + Context context = getApplicationContext(); CharSequence contentTitle = "OpenPilot"; CharSequence contentText = message; Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); - + msg.setLatestEventInfo(context, contentTitle, contentText, intent); - + mNManager.notify(id, msg); } - - public UAVObjectManager getObjMngr() { return objMngr; }; - public UAVTalk getUavTalk() { return uavTalk; }; - public Telemetry getTelemetry() { return tel; }; - public TelemetryMonitor getTelemetryMonitor() { return mon; }; - } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 6bb217930..48aa1cd10 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,21 @@ package org.openpilot.androidgcs; -import java.io.IOException; import java.util.Observable; import java.util.Observer; -import java.util.Set; -import java.util.UUID; -import android.app.Activity; -import android.bluetooth.BluetoothAdapter; -import android.bluetooth.BluetoothDevice; -import android.bluetooth.BluetoothSocket; -import android.content.Intent; import android.os.Bundle; import android.os.Handler; import android.util.Log; import android.widget.TextView; import android.widget.ToggleButton; -import org.openpilot.androidgcs.*; -import org.openpilot.uavtalk.Telemetry; -import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVTalk; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; -public class ObjectBrowser extends Activity { - +public class ObjectBrowser extends ObjectManagerActivity { + private final String TAG = "ObjectBrower"; - private final String DEVICE_NAME = "RN42-222D"; - private final int REQUEST_ENABLE_BT = 0; - private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); - BluetoothAdapter mBluetoothAdapter; - BluetoothSocket socket; boolean connected; - UAVObjectManager objMngr; - UAVTalk uavTalk; - + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -44,9 +23,9 @@ public class ObjectBrowser extends Activity { button.setChecked(!connected); Log.d(TAG,"HERE" + connected); - + TextView text = (TextView) findViewById(R.id.textView1); - + UAVObject obj1 = objMngr.getObject("SystemStats"); UAVObject obj2 = objMngr.getObject("AttitudeRaw"); UAVObject obj3 = objMngr.getObject("AttitudeActual"); @@ -57,52 +36,30 @@ public class ObjectBrowser extends Activity { Log.d(TAG,"And here"); text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + } }; - - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - setContentView(R.layout.main); - - Log.d(TAG, "Launching Object Browser"); - Log.d(TAG, "Start OP Telemetry Service"); - startService( new Intent( this, OPTelemetryService.class ) ); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + } + + @Override + void onOPConnected() { + // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Log.d(TAG, "onOPConnected()"); UAVObject obj = objMngr.getObject("SystemStats"); + Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } }); - obj = objMngr.getObject("AttitudeRaw"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("AttitudeActual"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("SystemAlarms"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - } - + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index 90ab80899..d316526ef 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -3,14 +3,10 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; import android.content.Context; -import android.content.Intent; -import android.os.Bundle; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { - private static boolean connected = false; - public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index c754c8329..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -630,7 +630,6 @@ public class Telemetry { /** * Private variables */ - private TelemetryStats stats; private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 9b4474d8e..7208181ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -8,9 +8,6 @@ import java.util.Observer; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; -import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; - import android.util.Log; public class TelemetryMonitor { @@ -26,7 +23,7 @@ public class TelemetryMonitor { private UAVObjectManager objMngr; private Telemetry tel; - private UAVObject objPending; +// private UAVObject objPending; private UAVObject gcsStatsObj; private UAVObject flightStatsObj; private Timer periodicTask; @@ -38,7 +35,7 @@ public class TelemetryMonitor { { this.objMngr = objMngr; this.tel = tel; - this.objPending = null; +// this.objPending = null; queue = new ArrayList(); // Get stats objects @@ -142,7 +139,7 @@ public class TelemetryMonitor { // Request update tel.updateRequested(obj); - objPending = obj; +// objPending = obj; } /** @@ -155,7 +152,7 @@ public class TelemetryMonitor { if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); - objPending = null; +// objPending = null; if(!success) { Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index ba3bf1ae3..940b076a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -64,7 +64,7 @@ public abstract class UAVObject { if(manually) updatedManual(); } - void updated() { updated(true); }; + public void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index de2059e90..78ad70630 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -1,6 +1,5 @@ package org.openpilot.uavtalk; -import java.io.Serializable; import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.ArrayList; @@ -91,7 +90,8 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public synchronized int pack(ByteBuffer dataOut) { + @SuppressWarnings("unchecked") + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -152,7 +152,8 @@ public class UAVObjectField { return getNumBytes(); } - public synchronized int unpack(ByteBuffer dataIn) { + @SuppressWarnings("unchecked") + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -436,9 +437,9 @@ public class UAVObjectField { } } - public String toString() { + public String toString() { String sout = new String(); - sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; + sout += name + ": " + data.toString() + " (" + units + ")\n"; return sout; } From e2a90b2265d721e1fc28f76b6630dfa979dc5fd8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 06:09:06 -0500 Subject: [PATCH 231/508] Added some missing files. Improved object browser to use ListView. ExpandableListView next. --- androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 0 -> 12288 bytes androidgcs/Doc/AndroidArchitecture.txt | 31 +++++++ androidgcs/res/layout/main.xml | 17 ++-- androidgcs/res/layout/object_view.xml | 7 ++ androidgcs/res/menu/options_menu.xml | 6 ++ androidgcs/res/values/strings.xml | 4 + androidgcs/res/xml/telemetry_widget_info.xml | 9 ++ .../androidgcs/OPTelemetryService.java | 69 +++++++++++--- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++----- .../androidgcs/ObjectManagerActivity.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 30 +++++-- .../src/org/openpilot/uavtalk/UAVTalk.java | 3 +- 12 files changed, 202 insertions(+), 59 deletions(-) create mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp create mode 100644 androidgcs/Doc/AndroidArchitecture.txt create mode 100644 androidgcs/res/layout/object_view.xml create mode 100644 androidgcs/res/menu/options_menu.xml create mode 100644 androidgcs/res/xml/telemetry_widget_info.xml diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp new file mode 100644 index 0000000000000000000000000000000000000000..167a072526a8207b396d71d6dd7d3e7a417cba19 GIT binary patch literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 literal 0 HcmV?d00001 diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt new file mode 100644 index 000000000..d9cdf2ada --- /dev/null +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -0,0 +1,31 @@ +------- TELEMETRY --------- +The Telemetry system has been implemented, and is composed of a few +major components: + +Telemetry.java - receives command to transmit objects through telemetry and +also emits notification when transactions are completed + +TelemetryMonitor.java - monitors the FlightTelemetryStats and GCSTelemetryStats +to establish when a working connection is in place. Also initiates downloading +all the objects on a new connection. + +UAVObjectManager.java - the central data store. The data is actually stored +within objects, but this maintains the handles to all of them. + +UAVTalk.java - the actual communication layer. Can packetize an object and +insert into stream and process the incoming stream and update objects +accordingly. + +---- MESSAGE PASSING ---- +The current implementation/analog to the slots/sockets in QT are Observers +which are registered as added to an Observable. This is used extensibly within +the telemetry system. I will continue to use this _within_ the Telemetry +module so it doesn't depend on any android features. + +In android there is a constraint that UI operations should all be done from the +UI thread. The most common way to do this is for the UI object (such as +Activity) to instantiate a Handler to which messages or runnables are posted. + +So for external objects they will register a runnable somehow... + + diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 9e5f90add..880e276ff 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -1,13 +1,6 @@ - - - - - + + + diff --git a/androidgcs/res/layout/object_view.xml b/androidgcs/res/layout/object_view.xml new file mode 100644 index 000000000..fdf5a0bae --- /dev/null +++ b/androidgcs/res/layout/object_view.xml @@ -0,0 +1,7 @@ + + + diff --git a/androidgcs/res/menu/options_menu.xml b/androidgcs/res/menu/options_menu.xml new file mode 100644 index 000000000..db86aa670 --- /dev/null +++ b/androidgcs/res/menu/options_menu.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 52fa56534..8daa0ec36 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,4 +1,8 @@ OpenPilot GCS + Settings + Connect + Disconnect + OpenPilot Object Browser diff --git a/androidgcs/res/xml/telemetry_widget_info.xml b/androidgcs/res/xml/telemetry_widget_info.xml new file mode 100644 index 000000000..f2ced6645 --- /dev/null +++ b/androidgcs/res/xml/telemetry_widget_info.xml @@ -0,0 +1,9 @@ + + + android:minWidth="294dp" + android:minHeight="72dp" + android:updatePeriodMillis="86400000" + android:initialLayout="@layout/telemetry_widget"> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 557c3b256..7b3030d4f 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -1,5 +1,8 @@ package org.openpilot.androidgcs; +import java.util.Observable; +import java.util.Observer; + import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVDataObject; @@ -27,7 +30,7 @@ import android.widget.Toast; public class OPTelemetryService extends Service { // Logging settings - private final String TAG = "OPTElemetryService"; + private final String TAG = "OPTelemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -44,10 +47,13 @@ public class OPTelemetryService extends Service { private ServiceHandler mServiceHandler; // Message ids - final int MSG_START = 0; - final int MSG_CONNECT_BT = 1; - final int MSG_CONNECT_FAKE = 2; - final int MSG_TOAST = 100; + static final int MSG_START = 0; + static final int MSG_CONNECT_BT = 1; + static final int MSG_CONNECT_FAKE = 2; + static final int MSG_DISCONNECT = 3; + static final int MSG_TOAST = 100; + + private boolean terminate = false; private Thread activeTelem; @@ -65,12 +71,28 @@ public class OPTelemetryService extends Service { System.out.println("HERE"); stopSelf(msg.arg2); case MSG_CONNECT_BT: + terminate = false; activeTelem = new BTTelemetryThread(); activeTelem.start(); break; case MSG_CONNECT_FAKE: + terminate = false; activeTelem = new FakeTelemetryThread(); activeTelem.start(); + break; + case MSG_DISCONNECT: + terminate = true; + try { + activeTelem.join(); + } catch (InterruptedException e) { + e.printStackTrace(); + } + activeTelem = null; + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_DISCONNECTED); + sendBroadcast(intent,null); + break; case MSG_TOAST: Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); @@ -129,8 +151,18 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_CONNECT_FAKE; mServiceHandler.sendMessage(msg); } + public void openBTConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_BT; + mServiceHandler.sendMessage(msg); + } + public void stopConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_DISCONNECT; + mServiceHandler.sendMessage(msg); + } }; - + public void toastMessage(String msgText) { Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_TOAST; @@ -151,17 +183,17 @@ public class OPTelemetryService extends Service { objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); } - + public void run() { - System.out.println("Runnin fake thread"); + System.out.println("Running fake thread"); Intent intent = new Intent(); intent.setAction(INTENT_ACTION_CONNECTED); sendBroadcast(intent,null); - + //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); - while(true) { + while( !terminate ) { systemStats.updated(); try { Thread.sleep(1000); @@ -176,7 +208,7 @@ public class OPTelemetryService extends Service { private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; - //private TelemetryMonitor mon; + private TelemetryMonitor mon; public UAVObjectManager getObjectManager() { return objMngr; }; @@ -217,10 +249,21 @@ public class OPTelemetryService extends Service { uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - new TelemetryMonitor(objMngr,tel); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); - while(true) { + while( !terminate ) { if( !uavTalk.processInputStream() ) break; } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 48aa1cd10..f68e839c1 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,67 @@ package org.openpilot.androidgcs; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; +import android.view.View; +import android.view.ViewGroup; +import android.widget.ArrayAdapter; +import android.widget.ExpandableListAdapter; +import android.widget.ExpandableListView; +import android.widget.ListView; +import android.widget.SimpleAdapter; +import android.widget.SimpleExpandableListAdapter; import android.widget.TextView; -import android.widget.ToggleButton; +import android.widget.Toast; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity { + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openBTConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + updateText.run(); + return true; + case R.id.menu_settings: + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + private final String TAG = "ObjectBrower"; boolean connected; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); - button.setChecked(!connected); - - Log.d(TAG,"HERE" + connected); - - TextView text = (TextView) findViewById(R.id.textView1); - - UAVObject obj1 = objMngr.getObject("SystemStats"); - UAVObject obj2 = objMngr.getObject("AttitudeRaw"); - UAVObject obj3 = objMngr.getObject("AttitudeActual"); - UAVObject obj4 = objMngr.getObject("SystemAlarms"); - - if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) - return; - - Log.d(TAG,"And here"); - text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + Log.d(TAG,"Update"); + update(); } }; @@ -44,16 +69,15 @@ public class ObjectBrowser extends ObjectManagerActivity { @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.main); } @Override void onOPConnected() { - // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + UAVObject obj = objMngr.getObject("SystemStats"); - Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { @@ -62,4 +86,18 @@ public class ObjectBrowser extends ObjectManagerActivity { }); } + + public void update() { + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 9f57796dc..12a072de7 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -85,7 +85,6 @@ public abstract class ObjectManagerActivity extends Activity { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); binder = (LocalBinder) service; - binder.openFakeConnection(); } public void onServiceDisconnected(ComponentName name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 7208181ad..daedcc85b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -10,10 +10,10 @@ import java.util.TimerTask; import android.util.Log; -public class TelemetryMonitor { +public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -31,6 +31,12 @@ public class TelemetryMonitor { private long lastUpdateTime; private List queue; + private boolean connected = false; + private boolean objects_updated = false; + + public boolean getConnected() { return connected; }; + public boolean getObjectsUpdated() { return objects_updated; }; + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) { this.objMngr = objMngr; @@ -116,8 +122,9 @@ public class TelemetryMonitor { if ( queue.isEmpty() ) { if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); - //qxtLog->debug("Object retrieval completed"); - //emit connected(); + objects_updated = true; + setChanged(); + notifyObservers(); return; } // Get next object from the queue @@ -260,9 +267,9 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; - boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; + boolean gcsConnected = statusField.getValue().equals("Connected"); + boolean gcsDisconnected = statusField.getValue().equals("Disconnected"); + boolean flightConnected = flightStatsObj.getField("Status").equals("Connected"); if ( !gcsConnected || !flightConnected ) { @@ -275,14 +282,21 @@ public class TelemetryMonitor { { if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); + connected = true; + objects_updated = false; startRetrievingObjects(); + setChanged(); } if (gcsDisconnected && gcsStatusChanged) { if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - //emit disconnected(); + connected = false; + objects_updated = false; + setChanged(); } + notifyObservers(); + } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8671cdef9..39c1f6ee7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -197,8 +197,7 @@ public class UAVTalk extends Observable { return false; } - // System.out.println("Received byte " + val + " in state + " + - // rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); return true; } From 68e0e27f75ed64fc3929fed6b1135d64faef5900 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 21:34:03 -0500 Subject: [PATCH 232/508] Added a home page, added an option to select connection type. Made the ListView adapter trigger updates on the data. --- androidgcs/AndroidManifest.xml | 8 ++- androidgcs/Doc/AndroidArchitecture.txt | 39 +++++++++++ androidgcs/res/layout/gcs_home.xml | 7 ++ androidgcs/res/values/arrays.xml | 15 +++++ androidgcs/res/values/strings.xml | 9 ++- androidgcs/res/xml/preferences.xml | 12 ++++ .../org/openpilot/androidgcs/HomePage.java | 23 +++++++ .../androidgcs/OPTelemetryService.java | 39 ++++++----- .../openpilot/androidgcs/ObjectBrowser.java | 65 ++++++++----------- .../androidgcs/ObjectManagerActivity.java | 28 ++++++++ .../org/openpilot/androidgcs/Preferences.java | 12 ++++ 11 files changed, 201 insertions(+), 56 deletions(-) create mode 100644 androidgcs/res/layout/gcs_home.xml create mode 100644 androidgcs/res/values/arrays.xml create mode 100644 androidgcs/res/xml/preferences.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/HomePage.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/Preferences.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 9a3d1dd25..a791d0fbb 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -10,17 +10,23 @@ - + + + + + + + diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt index d9cdf2ada..0a17a8dfa 100644 --- a/androidgcs/Doc/AndroidArchitecture.txt +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -16,6 +16,11 @@ UAVTalk.java - the actual communication layer. Can packetize an object and insert into stream and process the incoming stream and update objects accordingly. +** Threading +Currently object updates run within the thread of the function that called +update. This should be changed so that it adds a message to the Telemetry +thread which will then send on its own time. + ---- MESSAGE PASSING ---- The current implementation/analog to the slots/sockets in QT are Observers which are registered as added to an Observable. This is used extensibly within @@ -28,4 +33,38 @@ Activity) to instantiate a Handler to which messages or runnables are posted. So for external objects they will register a runnable somehow... +--- TELEMETRY SERVICE --- +The telemetry connection will be maintained by a service separate from the the +main activity(s). Although it is a bit unusual, the service will support being +started and stopped, as well as being bound. Binding will be required to get +access to the Object Manager. +In addition, to make it forward looking, the start intent can specify a +connection to open. This will allow the service in future to monitor multiple +connections. + +The service will destroy itself only when all active connections disappear and +all activies are unbound. + +It will also handle any logging desired (I think). + +There will be a primary message handler thread. This thread will separately +launch telemetry threads when required. + +The service should send broadcast intents whenever a connection is estabilished +or dropped. + +I dont think the service should have the options about which UAVs are +supported. + +** Telemetry IBinder +*** Give handle to the ObjectManager for each UAV +*** Call disconnect +*** Query conncetion status + +--- TELEMETRY WIDGET --- +Listens for conncet/disconnect intents + +Also show if service is running? + +Ability to launch service? diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml new file mode 100644 index 000000000..e6f4ea567 --- /dev/null +++ b/androidgcs/res/layout/gcs_home.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/res/values/arrays.xml b/androidgcs/res/values/arrays.xml new file mode 100644 index 000000000..18ee52298 --- /dev/null +++ b/androidgcs/res/values/arrays.xml @@ -0,0 +1,15 @@ + + + + None + Fake + Bluetooth + Network + + + 0 + 1 + 2 + 3 + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 8daa0ec36..e9b66a312 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,8 +1,13 @@ - OpenPilot GCS + OpenPilot GCS Home + OpenPilot Object Browser Settings Connect Disconnect - OpenPilot Object Browser + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml new file mode 100644 index 000000000..d731f59dd --- /dev/null +++ b/androidgcs/res/xml/preferences.xml @@ -0,0 +1,12 @@ + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java new file mode 100644 index 000000000..478c7cdca --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -0,0 +1,23 @@ +package org.openpilot.androidgcs; + +import android.content.Intent; +import android.os.Bundle; +import android.view.View; +import android.view.View.OnClickListener; +import android.widget.Button; + +public class HomePage extends ObjectManagerActivity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); + objectBrowser.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, ObjectBrowser.class)); + } + }); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 7b3030d4f..5af7c7d60 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -16,6 +16,7 @@ import android.app.PendingIntent; import android.app.Service; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; import android.net.Uri; import android.os.Binder; import android.os.Handler; @@ -24,6 +25,7 @@ import android.os.IBinder; import android.os.Looper; import android.os.Message; import android.os.Process; +import android.preference.PreferenceManager; import android.util.Log; import android.widget.Toast; @@ -48,8 +50,7 @@ public class OPTelemetryService extends Service { // Message ids static final int MSG_START = 0; - static final int MSG_CONNECT_BT = 1; - static final int MSG_CONNECT_FAKE = 2; + static final int MSG_CONNECT = 1; static final int MSG_DISCONNECT = 3; static final int MSG_TOAST = 100; @@ -70,14 +71,22 @@ public class OPTelemetryService extends Service { Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT_BT: + case MSG_CONNECT: terminate = false; - activeTelem = new BTTelemetryThread(); - activeTelem.start(); - break; - case MSG_CONNECT_FAKE: - terminate = false; - activeTelem = new FakeTelemetryThread(); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + int connection_type = Integer.decode(prefs.getString("connection_type", "")); + switch(connection_type) { + case 0: // No connection + return; + case 1: + activeTelem = new FakeTelemetryThread(); + break; + case 2: + activeTelem = new BTTelemetryThread(); + break; + case 3: + throw new Error("Unsupported"); + } activeTelem.start(); break; case MSG_DISCONNECT: @@ -146,14 +155,9 @@ public class OPTelemetryService extends Service { public TelemTask getTelemTask(int id) { return (TelemTask) activeTelem; } - public void openFakeConnection() { + public void openConnection() { Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_FAKE; - mServiceHandler.sendMessage(msg); - } - public void openBTConnection() { - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_BT; + msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); } public void stopConnection() { @@ -161,6 +165,9 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_DISCONNECT; mServiceHandler.sendMessage(msg); } + public boolean isConnected() { + return activeTelem != null; + } }; public void toastMessage(String msgText) { diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f68e839c1..f3cc56d47 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -6,15 +6,20 @@ import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.content.Intent; +import android.content.SharedPreferences; +import android.content.SharedPreferences.OnSharedPreferenceChangeListener; import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; +import android.preference.PreferenceManager; import android.util.Log; import android.view.Menu; import android.view.MenuInflater; import android.view.MenuItem; import android.view.View; import android.view.ViewGroup; +import android.widget.Adapter; import android.widget.ArrayAdapter; import android.widget.ExpandableListAdapter; import android.widget.ExpandableListView; @@ -27,36 +32,13 @@ import android.widget.Toast; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; -public class ObjectBrowser extends ObjectManagerActivity { - - @Override - public boolean onOptionsItemSelected(MenuItem item) { - switch(item.getItemId()) { - case R.id.menu_connect: - binder.openBTConnection(); - return true; - case R.id.menu_disconnect: - binder.stopConnection(); - updateText.run(); - return true; - case R.id.menu_settings: - return true; - default: - return super.onOptionsItemSelected(item); - } - - } - - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); - inflater.inflate(R.menu.options_menu, menu); - return true; - } +public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; boolean connected; - + SharedPreferences prefs; + ArrayAdapter adapter; + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -70,6 +52,8 @@ public class ObjectBrowser extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.main); + prefs = PreferenceManager.getDefaultSharedPreferences(this); + prefs.registerOnSharedPreferenceChangeListener(this); } @Override @@ -77,6 +61,17 @@ public class ObjectBrowser extends ObjectManagerActivity { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -88,16 +83,12 @@ public class ObjectBrowser extends ObjectManagerActivity { } public void update() { - List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); - ListIterator> li = allobjects.listIterator(); - while(li.hasNext()) { - linearized.addAll(li.next()); - } - - ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); - ListView objects = (ListView) findViewById(R.id.object_list); - objects.setAdapter(adapter); + adapter.notifyDataSetChanged(); + } + public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, + String key) { + // TODO Auto-generated method stub + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 12a072de7..d91946b92 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -14,6 +14,9 @@ import android.content.ServiceConnection; import android.os.Bundle; import android.os.IBinder; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { @@ -72,6 +75,31 @@ public abstract class ObjectManagerActivity extends Activity { } + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + @Override public void onStart() { super.onStart(); diff --git a/androidgcs/src/org/openpilot/androidgcs/Preferences.java b/androidgcs/src/org/openpilot/androidgcs/Preferences.java new file mode 100644 index 000000000..913de0f73 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/Preferences.java @@ -0,0 +1,12 @@ +package org.openpilot.androidgcs; + +import android.os.Bundle; +import android.preference.PreferenceActivity; + +public class Preferences extends PreferenceActivity { + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + addPreferencesFromResource(R.xml.preferences); + } +} From 545dd029d6d8e2a2c52b255f5e8cf5897250c471 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 21 Mar 2011 18:33:47 -0500 Subject: [PATCH 233/508] More work on the object browser/editor. Hard to make it resize itself though. --- androidgcs/AndroidManifest.xml | 1 + androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 12288 -> 0 bytes .../layout/{main.xml => object_browser.xml} | 0 androidgcs/res/layout/object_edit.xml | 9 +++ .../openpilot/androidgcs/ObjectBrowser.java | 44 ++++++++------- .../openpilot/androidgcs/ObjectEditor.java | 52 ++++++++++++++++++ .../androidgcs/ObjectManagerActivity.java | 23 +++++++- 7 files changed, 108 insertions(+), 21 deletions(-) delete mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp rename androidgcs/res/layout/{main.xml => object_browser.xml} (100%) create mode 100644 androidgcs/res/layout/object_edit.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index a791d0fbb..fe8c6ae9a 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -26,6 +26,7 @@ + diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp deleted file mode 100644 index 167a072526a8207b396d71d6dd7d3e7a417cba19..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/object_browser.xml similarity index 100% rename from androidgcs/res/layout/main.xml rename to androidgcs/res/layout/object_browser.xml diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml new file mode 100644 index 000000000..62a482be9 --- /dev/null +++ b/androidgcs/res/layout/object_edit.xml @@ -0,0 +1,9 @@ + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f3cc56d47..df2d114a4 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -9,25 +9,16 @@ import java.util.Observer; import android.content.Intent; import android.content.SharedPreferences; import android.content.SharedPreferences.OnSharedPreferenceChangeListener; -import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.preference.PreferenceManager; import android.util.Log; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.View; -import android.view.ViewGroup; -import android.widget.Adapter; +import android.widget.AdapterView; import android.widget.ArrayAdapter; -import android.widget.ExpandableListAdapter; -import android.widget.ExpandableListView; import android.widget.ListView; -import android.widget.SimpleAdapter; -import android.widget.SimpleExpandableListAdapter; -import android.widget.TextView; import android.widget.Toast; +import android.widget.AdapterView.OnItemClickListener; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; @@ -38,6 +29,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref boolean connected; SharedPreferences prefs; ArrayAdapter adapter; + List allObjects; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { @@ -51,7 +43,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); } @@ -60,18 +52,32 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); + allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - linearized.addAll(li.next()); + allObjects.addAll(li.next()); } - - adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + + adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); ListView objects = (ListView) findViewById(R.id.object_list); objects.setAdapter(adapter); + objects.setOnItemClickListener(new OnItemClickListener() { + public void onItemClick(AdapterView parent, View view, + int position, long id) { + /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), + Toast.LENGTH_SHORT).show();*/ + Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); + intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); + intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); + intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); + startActivity(intent); + } + }); + + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -81,7 +87,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref }); } - + public void update() { adapter.notifyDataSetChanged(); } @@ -89,6 +95,6 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, String key) { // TODO Auto-generated method stub - + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java new file mode 100644 index 000000000..33d0e2f8e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -0,0 +1,52 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectField; + +import android.os.Bundle; +import android.widget.LinearLayout; +import android.widget.TextView; +import android.widget.Toast; + +public class ObjectEditor extends ObjectManagerActivity { + + String objectName; + int objectID; + int instID; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.object_edit); + + System.out.println("Started. Intent:" + getIntent()); + Bundle extras = getIntent().getExtras(); + if(extras != null){ + objectName = extras.getString("org.openpilot.androidgcs.ObjectName"); + objectID = extras.getInt("org.openpilot.androidgcs.ObjectId"); + instID = extras.getInt("org.openpilot.androidgcs.InstId"); + } + } + + public void onOPConnected() { + UAVObject obj = objMngr.getObject(objectID, instID); + Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); + + TextView objectName = (TextView) findViewById(R.id.object_edit_name); + objectName.setText(obj.getName()); + + LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); + List fields = obj.getFields(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + TextView fieldName = new TextView(this); + fieldName.setText(field.getName()); + fieldViewList.addView(fieldName); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index d91946b92..5027d4d24 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -21,7 +21,7 @@ import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { private final String TAG = "ObjectManagerActivity"; - private static int LOGLEVEL = 2; + private static int LOGLEVEL = 0; // private static boolean WARN = LOGLEVEL > 1; private static boolean DEBUG = LOGLEVEL > 0; @@ -106,19 +106,38 @@ public abstract class ObjectManagerActivity extends Activity { Intent intent = new Intent(this, OPTelemetryService.class); bindService(intent, mConnection, Context.BIND_AUTO_CREATE); } + + public void onBind() { + + } /** Defines callbacks for service binding, passed to bindService() */ private ServiceConnection mConnection = new ServiceConnection() { public void onServiceConnected(ComponentName arg0, IBinder service) { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); - binder = (LocalBinder) service; + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } } public void onServiceDisconnected(ComponentName name) { mBound = false; + binder = null; mConnected = false; objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); } }; } From 5669a3fc33a7faa1f96273c49572f433101ff53f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:01 -0500 Subject: [PATCH 234/508] Added a simple PFD --- androidgcs/AndroidManifest.xml | 9 +- androidgcs/res/drawable-hdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-ldpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-mdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/layout/gcs_home.xml | 9 +- androidgcs/res/layout/pfd.xml | 8 + androidgcs/res/values/colors.xml | 6 + androidgcs/res/values/strings.xml | 6 + .../openpilot/androidgcs/AttitudeView.java | 89 +++++++++++ .../org/openpilot/androidgcs/CompassView.java | 139 ++++++++++++++++++ .../org/openpilot/androidgcs/HomePage.java | 9 ++ .../src/org/openpilot/androidgcs/PFD.java | 51 +++++++ 12 files changed, 318 insertions(+), 8 deletions(-) create mode 100644 androidgcs/res/drawable-hdpi/browser_icon.png create mode 100644 androidgcs/res/drawable-ldpi/browser_icon.png create mode 100644 androidgcs/res/drawable-mdpi/browser_icon.png create mode 100644 androidgcs/res/layout/pfd.xml create mode 100644 androidgcs/res/values/colors.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/AttitudeView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/CompassView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/PFD.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index fe8c6ae9a..1942146c4 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,13 +18,8 @@ - - - - - - - + + diff --git a/androidgcs/res/drawable-hdpi/browser_icon.png b/androidgcs/res/drawable-hdpi/browser_icon.png new file mode 100644 index 0000000000000000000000000000000000000000..3fcee485245922172e66bad2eb2203db14cdac39 GIT binary patch literal 456 zcmV;(0XP1MP)2!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y0000 - + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml new file mode 100644 index 000000000..191a80eb9 --- /dev/null +++ b/androidgcs/res/layout/pfd.xml @@ -0,0 +1,8 @@ + + + + + diff --git a/androidgcs/res/values/colors.xml b/androidgcs/res/values/colors.xml new file mode 100644 index 000000000..dc8eaf315 --- /dev/null +++ b/androidgcs/res/values/colors.xml @@ -0,0 +1,6 @@ + + + #F555 + #AFFF + #AFFF + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index e9b66a312..3b3a38d02 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -2,6 +2,7 @@ OpenPilot GCS Home OpenPilot Object Browser + OpenPilot PFD Settings Connect Disconnect @@ -10,4 +11,9 @@ Connection Type Bluetooth Select the connection method + Compass + N + E + S + W diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java new file mode 100644 index 000000000..24a8bf5f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -0,0 +1,89 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class AttitudeView extends View { + + public AttitudeView(Context context) { + super(context); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats) { + super(context, ats); + initAttitudeView(); + } + + protected void initAttitudeView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double roll; + public void setRoll(double roll) { + this.roll = roll; + } + private double pitch; + public void setPitch(double d) { + this.pitch = d; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + + canvas.drawLine(px,py, (int) (px+radius * Math.cos(roll)), (int) (py + radius * Math.sin(roll)), markerPaint); + canvas.drawLine(px,py, (int) (px+radius * Math.cos(pitch)), (int) (py + radius * Math.sin(pitch)), markerPaint); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/CompassView.java b/androidgcs/src/org/openpilot/androidgcs/CompassView.java new file mode 100644 index 000000000..50e4abc0a --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/CompassView.java @@ -0,0 +1,139 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class CompassView extends View { + + public CompassView(Context context) { + super(context); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats) { + super(context, ats); + initCompassView(); + } + + protected void initCompassView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + northString = r.getString(R.string.cardinal_north); + eastString = r.getString(R.string.cardinal_east); + southString = r.getString(R.string.cardinal_south); + westString = r.getString(R.string.cardinal_west); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + textHeight = (int)textPaint.measureText("yY"); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double bearing; + public void setBearing(double bearing) { + this.bearing = bearing; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + private String northString; + private String eastString; + private String southString; + private String westString; + private int textHeight; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + // Draw the background + canvas.drawCircle(px, py, radius, circlePaint); + + // Rotate our perspective so that the ÔtopÕ is + // facing the current bearing. + canvas.save(); + canvas.rotate((float) -bearing, px, py); + + int textWidth = (int)textPaint.measureText("W"); + int cardinalX = px-textWidth/2; + int cardinalY = py-radius+textHeight; + + // Draw the marker every 15 degrees and text every 45. + for (int i = 0; i < 24; i++) { + // Draw a marker. + canvas.drawLine(px, py-radius, px, py-radius+10, markerPaint); + canvas.save(); + canvas.translate(0, textHeight); + // Draw the cardinal points + if (i % 6 == 0) { + String dirString = null; + switch (i) { + case 0 : { + dirString = northString; + int arrowY = 2*textHeight; + canvas.drawLine(px, arrowY, px-5, 3*textHeight, markerPaint); + canvas.drawLine(px, arrowY, px+5, 3*textHeight, markerPaint); + break; + } + case 6: dirString = eastString; break; + case 12: dirString = southString; break; + case 18: dirString = westString; break; + } + canvas.drawText(dirString, cardinalX, cardinalY, textPaint); + } + else if (i % 3 == 0) { + // Draw the text every alternate 45deg + String angle = String.valueOf(i*15); + float angleTextWidth = textPaint.measureText(angle); + + int angleTextX = (int)(px-angleTextWidth/2); + int angleTextY = py-radius+textHeight; + canvas.drawText(angle, angleTextX, angleTextY, textPaint); + } + canvas.restore(); + canvas.rotate(15, px, py); + } + canvas.restore(); + } +} diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 478c7cdca..7d03e1b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -12,12 +12,21 @@ public class HomePage extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); objectBrowser.setOnClickListener(new OnClickListener() { public void onClick(View arg0) { startActivity(new Intent(HomePage.this, ObjectBrowser.class)); } }); + + Button pfd = (Button) findViewById(R.id.launch_pfd); + pfd.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, PFD.class)); + } + }); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PFD.java b/androidgcs/src/org/openpilot/androidgcs/PFD.java new file mode 100644 index 000000000..e0d1b9f24 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/PFD.java @@ -0,0 +1,51 @@ +package org.openpilot.androidgcs; + +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; + +import android.os.Bundle; + +public class PFD extends ObjectManagerActivity { + + double heading; + double roll; + double pitch; + + Runnable update = new Runnable() { + public void run() { + CompassView compass = (CompassView) findViewById(R.id.compass_view); + compass.setBearing((int) heading); + compass.invalidate(); + + AttitudeView attitude = (AttitudeView) findViewById(R.id.attitude_view); + attitude.setRoll(roll / 180 * Math.PI); + attitude.setPitch(pitch / 180 * Math.PI); + attitude.invalidate(); + } + }; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.pfd); + } + + @Override + void onOPConnected() { + + UAVObject obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + heading = obj.getField("Yaw").getDouble(); + pitch = obj.getField("Pitch").getDouble(); + roll = obj.getField("Roll").getDouble(); + runOnUiThread(update); + } + }); + } +} From 56aca6a8ec5960a39541377c61e7629bbf1e0056 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:17 -0500 Subject: [PATCH 235/508] Make fake telemetry show rotating attitude. --- .../org/openpilot/androidgcs/OPTelemetryService.java | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5af7c7d60..43cc13b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -200,8 +200,19 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + double roll = 0; + double pitch = 0; + double yaw = 0; while( !terminate ) { + attitudeActual.getField("Roll").setDouble(roll); + attitudeActual.getField("Pitch").setDouble(pitch); + attitudeActual.getField("Yaw").setDouble(yaw); + roll = (roll + 10) % 180; + pitch = (pitch + 10) % 180; + yaw = (yaw + 10) % 360; systemStats.updated(); + attitudeActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { From 936ec069668626906559f05722c6b03459a47c4a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 13:14:11 -0500 Subject: [PATCH 236/508] Make auto starting work. For now removed support for standalone service but easy to add back. --- .../androidgcs/OPTelemetryService.java | 43 ++++++++++++------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 43cc13b04..67ee56d4e 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -68,10 +68,10 @@ public class OPTelemetryService extends Service { public void handleMessage(Message msg) { switch(msg.arg1) { case MSG_START: - Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); - System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT: + break; + case MSG_CONNECT: + Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); int connection_type = Integer.decode(prefs.getString("connection_type", "")); @@ -90,6 +90,7 @@ public class OPTelemetryService extends Service { activeTelem.start(); break; case MSG_DISCONNECT: + Toast.makeText(getApplicationContext(), "Disconnct", Toast.LENGTH_SHORT).show(); terminate = true; try { activeTelem.join(); @@ -101,6 +102,8 @@ public class OPTelemetryService extends Service { Intent intent = new Intent(); intent.setAction(INTENT_ACTION_DISCONNECTED); sendBroadcast(intent,null); + + stopSelf(); break; case MSG_TOAST: @@ -113,9 +116,9 @@ public class OPTelemetryService extends Service { } }; - @Override - public void onCreate() { - // Low priority thread for message handling with service + public void startup() { + Toast.makeText(getApplicationContext(), "Telemetry service starting", Toast.LENGTH_SHORT).show(); + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", Process.THREAD_PRIORITY_BACKGROUND); thread.start(); @@ -123,20 +126,27 @@ public class OPTelemetryService extends Service { // Get the HandlerThread's Looper and use it for our Handler mServiceLooper = thread.getLooper(); mServiceHandler = new ServiceHandler(mServiceLooper); + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + if(prefs.getBoolean("autoconnect", false)) { + Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT; + msg.arg2 = 0; + mServiceHandler.sendMessage(msg); + } + + } + + @Override + public void onCreate() { + startup(); } @Override public int onStartCommand(Intent intent, int flags, int startId) { - Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); - - System.out.println("Start"); - // For each start request, send a message to start a job and deliver the - // start ID so we know which request we're stopping when we finish the job - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_START; - msg.arg2 = startId; - mServiceHandler.sendMessage(msg); - + // Currently only using as bound service + // If we get killed, after returning from here, restart return START_STICKY; } @@ -156,6 +166,7 @@ public class OPTelemetryService extends Service { return (TelemTask) activeTelem; } public void openConnection() { + Toast.makeText(getApplicationContext(), "Requested open connection", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); From 3f5be92cc3eddec44db16fdf5f4f6a7bb14925ca Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:39:44 -0500 Subject: [PATCH 237/508] Added location feature and made fake stream create movement --- androidgcs/AndroidManifest.xml | 18 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/gcs_home.xml | 1 + androidgcs/res/layout/map_layout.xml | 10 + androidgcs/res/values/strings.xml | 37 ++- .../org/openpilot/androidgcs/HomePage.java | 6 + .../androidgcs/OPTelemetryService.java | 27 ++ .../org/openpilot/androidgcs/UAVLocation.java | 273 ++++++++++++++++++ 8 files changed, 351 insertions(+), 23 deletions(-) create mode 100644 androidgcs/res/layout/map_layout.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/UAVLocation.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 1942146c4..c18dc0cb1 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -4,10 +4,14 @@ android:versionName="1.0"> + + + + @@ -16,13 +20,15 @@ - - + + - - - - + + + + + diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 66db0d159..420db56e3 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-10 +target=Google Inc.:Google APIs:8 diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index 1a5a81cd7..e07f5b003 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -11,4 +11,5 @@ android:id="@+id/launch_object_browser" android:drawableLeft="@drawable/browser_icon" android:layout_centerHorizontal="true"/> + diff --git a/androidgcs/res/layout/map_layout.xml b/androidgcs/res/layout/map_layout.xml new file mode 100644 index 000000000..64c64b16e --- /dev/null +++ b/androidgcs/res/layout/map_layout.xml @@ -0,0 +1,10 @@ + + + + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 3b3a38d02..7cef563e7 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,19 +1,24 @@ - OpenPilot GCS Home - OpenPilot Object Browser - OpenPilot PFD - Settings - Connect - Disconnect - Settings - Automatically Connect - Connection Type - Bluetooth - Select the connection method - Compass - N - E - S - W + OpenPilot GCS Home + OpenPilot Object Browser + OpenPilot PFD + OpenPilot Location + + Settings + Connect + Disconnect + + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method + + Compass + N + E + S + W + Connected diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 7d03e1b04..cf9664d14 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -27,6 +27,12 @@ public class HomePage extends ObjectManagerActivity { } }); + Button location = (Button) findViewById(R.id.launch_location); + location.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, UAVLocation.class)); + } + }); } } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 67ee56d4e..c2914f34a 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -212,18 +212,45 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + UAVDataObject homeLocation = (UAVDataObject) objMngr.getObject("HomeLocation"); + UAVDataObject positionActual = (UAVDataObject) objMngr.getObject("PositionActual"); + + homeLocation.getField("Latitude").setDouble(379420315); + homeLocation.getField("Longitude").setDouble(-88330078); + homeLocation.getField("ECEF").setDouble(497665694,0); + homeLocation.getField("ECEF").setDouble(-77336320,1); + homeLocation.getField("ECEF").setDouble(390037169,2); + homeLocation.getField("RNE").setDouble(-0.60757166,0); + homeLocation.getField("RNE").setDouble(0.09441550,1); + homeLocation.getField("RNE").setDouble(0.78863323,2); + homeLocation.getField("RNE").setDouble(0.15355512,3); + homeLocation.getField("RNE").setDouble(0.98814011,4); + homeLocation.getField("RNE").setDouble(0,5); + homeLocation.getField("RNE").setDouble(-0.77928013,6); + homeLocation.getField("RNE").setDouble(0.12109867,7); + homeLocation.getField("RNE").setDouble(-0.61486387,8); + homeLocation.getField("Be").setDouble(26702.78710938,0); + homeLocation.getField("Be").setDouble(-1468.33605957,1); + homeLocation.getField("Be").setDouble(34181.78515625,2); + + double roll = 0; double pitch = 0; double yaw = 0; + double north = 0; + double east = 0; while( !terminate ) { attitudeActual.getField("Roll").setDouble(roll); attitudeActual.getField("Pitch").setDouble(pitch); attitudeActual.getField("Yaw").setDouble(yaw); + positionActual.getField("North").setDouble(north += 100); + positionActual.getField("East").setDouble(east += 100); roll = (roll + 10) % 180; pitch = (pitch + 10) % 180; yaw = (yaw + 10) % 360; systemStats.updated(); attitudeActual.updated(); + positionActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { diff --git a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java new file mode 100644 index 000000000..72085c1d6 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java @@ -0,0 +1,273 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectManager; + +import com.google.android.maps.GeoPoint; +import com.google.android.maps.MapActivity; +import com.google.android.maps.MapController; +import com.google.android.maps.MapView; +import com.google.android.maps.Overlay; +import com.google.android.maps.Projection; + +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.graphics.Point; +import android.graphics.RectF; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; + +public class UAVLocation extends MapActivity +{ + private final String TAG = "UAVLocation"; + private static int LOGLEVEL = 0; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + private MapView mapView; + private MapController mapController; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + GeoPoint homeLocation; + GeoPoint uavLocation; + + @Override public void onCreate(Bundle icicle) { + super.onCreate(icicle); + setContentView(R.layout.map_layout); + mapView = (MapView)findViewById(R.id.map_view); + mapController = mapView.getController(); + + mapView.displayZoomControls(true); + Double lat = 37.422006*1E6; + Double lng = -122.084095*1E6; + homeLocation = new GeoPoint(lat.intValue(), lng.intValue()); + uavLocation = homeLocation; + mapController.setCenter(homeLocation); + mapController.setZoom(18); + + List overlays = mapView.getOverlays(); + UAVOverlay myOverlay = new UAVOverlay(); + overlays.add(myOverlay); + mapView.postInvalidate(); + + // ObjectManager related stuff (can't inherit standard class) + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + //@Override + protected boolean isRouteDisplayed() { + // IMPORTANT: This method must return true if your Activity // is displaying driving directions. Otherwise return false. + return false; + } + + public class UAVOverlay extends Overlay { + @Override + public void draw(Canvas canvas, MapView mapView, boolean shadow) { + + Projection projection = mapView.getProjection(); + + if (shadow == false) { + Point myPoint = new Point(); + projection.toPixels(uavLocation, myPoint); + + //// Draw UAV + // Create and setup your paint brush + Paint paint = new Paint(); + paint.setARGB(250, 255, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + int rad = 5; + RectF oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("UAV", myPoint.x+rad, myPoint.y, paint); + + //// Draw Home + myPoint = new Point(); + projection.toPixels(homeLocation, myPoint); + + // Create and setup your paint brush + paint.setARGB(250, 0, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + rad = 5; + oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("Home", myPoint.x+rad, myPoint.y, paint); + + } + } + + @Override + public boolean onTap(GeoPoint point, MapView mapView1) { + // Return true if screen tap is handled by this overlay + return false; + } + } + + void onOPConnected() { + UAVObject obj = objMngr.getObject("HomeLocation"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double lat = obj.getField("Latitude").getDouble() / 10; + Double lon = obj.getField("Longitude").getDouble() / 10; + homeLocation = new GeoPoint(lat.intValue(), lon.intValue()); + runOnUiThread(new Runnable() { + public void run() { + mapController.setCenter(homeLocation); + } + }); + System.out.println("HomeLocation: " + homeLocation.toString()); + } + }); + // Hacky - trigger an update + obj.updated(); + + obj = objMngr.getObject("PositionActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double north = obj.getField("North").getDouble(); + Double east = obj.getField("East").getDouble(); + // TODO: Correct convertion from NED to LLA. This is erroneous conversion from cm to deg + uavLocation = new GeoPoint((int) (homeLocation.getLatitudeE6() + north / 100 * 1e6 / 78847), + (int) (homeLocation.getLongitudeE6() + east / 100 * 1e6 / 78847)); + runOnUiThread(new Runnable() { + public void run() { + mapView.invalidate(); + } + }); + } + }); + + } + + void onOPDisconnected() { + + } + + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + public void onBind() { + + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + binder = null; + mConnected = false; + objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); + } + }; +} From 1a4db3332859acf2218083bdd4cc2e8db7639063 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:59:36 -0500 Subject: [PATCH 238/508] Few tweaks and suppress some warnings --- androidgcs/default.properties | 2 +- androidgcs/res/xml/preferences.xml | 23 ++++++++++-------- .../openpilot/androidgcs/TelemetryWidget.java | 24 ++++++++++++++++++- .../uavobjects/UAVObjectsInitialize.java | 2 +- 4 files changed, 38 insertions(+), 13 deletions(-) diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 420db56e3..728f51f97 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:8 +target=Google Inc.:Google APIs:11 diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index d731f59dd..24fd43b5e 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -1,12 +1,15 @@ - - - + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index d316526ef..51afdf568 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -2,11 +2,34 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; +import android.content.ComponentName; import android.content.Context; +import android.content.Intent; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { + @Override + public void onReceive(Context context, Intent intent) { + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_CONNECTED)) { + changeStatus(context, true); + } + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_DISCONNECTED)) { + changeStatus(context, false); + } + + super.onReceive(context, intent); + } + + public void changeStatus(Context context, boolean status) { + RemoteViews updateViews = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); + updateViews.setTextViewText(R.id.telemetryWidgetStatus, "Connection status: " + status); + ComponentName thisWidget = new ComponentName(context, TelemetryWidget.class); + AppWidgetManager manager = AppWidgetManager.getInstance(context); + manager.updateAppWidget(thisWidget, updateViews); + + } + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; @@ -16,7 +39,6 @@ public class TelemetryWidget extends AppWidgetProvider { // Get the layout for the App Widget and attach an on-click listener to the button RemoteViews views = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); - //views.setOnClickPendingIntent(R.id.button, pendingIntent); // Tell the AppWidgetManager to perform an update on the current App Widget appWidgetManager.updateAppWidget(appWidgetId, views); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 4eca6ea82..d1d47aebb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,7 +28,7 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.uavobjects.*; +//import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { From caeaa0169f13587531154d792714abb52425244c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 23 Mar 2011 11:37:20 -0500 Subject: [PATCH 239/508] Cleaner editor interface --- androidgcs/default.properties | 2 +- androidgcs/res/layout/object_browser.xml | 3 +- androidgcs/res/layout/object_edit.xml | 6 +- androidgcs/res/layout/object_editor.xml | 6 + androidgcs/res/values/strings.xml | 3 + .../androidgcs/OPTelemetryService.java | 5 +- .../openpilot/androidgcs/ObjectBrowser.java | 3 + .../openpilot/androidgcs/ObjectEditView.java | 114 ++++++++++++++++++ .../openpilot/androidgcs/ObjectEditor.java | 12 +- 9 files changed, 138 insertions(+), 16 deletions(-) create mode 100644 androidgcs/res/layout/object_editor.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 728f51f97..fd1cedd24 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:11 +target=Google Inc.:Google APIs:10 diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 880e276ff..9c7456915 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,5 +2,6 @@ - + + diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml index 62a482be9..c161caa4c 100644 --- a/androidgcs/res/layout/object_edit.xml +++ b/androidgcs/res/layout/object_edit.xml @@ -3,7 +3,7 @@ xmlns:android="http://schemas.android.com/apk/res/android" android:layout_width="match_parent" android:layout_height="match_parent"> - - - + + + diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml new file mode 100644 index 000000000..d93b1a097 --- /dev/null +++ b/androidgcs/res/layout/object_editor.xml @@ -0,0 +1,6 @@ + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 7cef563e7..6d69e4126 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -21,4 +21,7 @@ S W Connected + Update + Save + Send diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index c2914f34a..ce90f5a48 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -74,7 +74,8 @@ public class OPTelemetryService extends Service { Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + //int connection_type = Integer.decode(prefs.getString("connection_type", "")); + int connection_type = 1; switch(connection_type) { case 0: // No connection return; @@ -128,7 +129,7 @@ public class OPTelemetryService extends Service { mServiceHandler = new ServiceHandler(mServiceLooper); SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - if(prefs.getBoolean("autoconnect", false)) { + if(prefs.getBoolean("autoconnect", false) || true) { Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index df2d114a4..a6ed177a2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -17,6 +17,7 @@ import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; import android.widget.ListView; +import android.widget.Spinner; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -46,6 +47,8 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); + + Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java new file mode 100644 index 000000000..7b81ff18c --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -0,0 +1,114 @@ +package org.openpilot.androidgcs; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectField; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.EditText; +import android.widget.LinearLayout; +import android.widget.TextView; + +public class ObjectEditView extends LinearLayout { + + TextView objectName; + List fields; + + public ObjectEditView(Context context) { + super(context); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats) { + super(context, ats); + initObjectEditView(); + } + + public void initObjectEditView() { + // Set orientation of layout to vertical + setOrientation(LinearLayout.VERTICAL); + + objectName = new TextView(getContext()); + objectName.setText(""); + objectName.setTextSize(14); + + // Lay them out in the compound control. + int lHeight = LayoutParams.WRAP_CONTENT; + int lWidth = LayoutParams.FILL_PARENT; + addView(objectName, new LinearLayout.LayoutParams(lWidth, lHeight)); + + fields = new ArrayList(); + } + + public void setName(String name) { + objectName.setText(name); + } + + public void addField(UAVObjectField field) { + if(field.getNumElements() == 1) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble()).toString()); + } else { + fieldView.setValue(field.getValue().toString()); + } + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + } + else { + ListIterator names = field.getElementNames().listIterator(); + int i = 0; + while(names.hasNext()) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName() + "-" + names.next()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble(i)).toString()); + } else { + fieldView.setValue(field.getValue(i).toString()); + } + i++; + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + + } + } + } + + public class FieldValue extends LinearLayout { + + TextView fieldName; + EditText fieldValue; + + public FieldValue(Context context) { + super(context); + setOrientation(LinearLayout.HORIZONTAL); + + fieldName = new TextView(getContext()); + fieldValue = new EditText(getContext()); + + // Lay them out in the compound control. + addView(fieldName, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + fieldValue.setWidth(300); + addView(fieldValue, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + } + + public void setName(String name) { + fieldName.setText(name); + } + + public void setValue(String value) { + fieldValue.setText(value); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java index 33d0e2f8e..afbddb5e5 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -7,8 +7,6 @@ import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectField; import android.os.Bundle; -import android.widget.LinearLayout; -import android.widget.TextView; import android.widget.Toast; public class ObjectEditor extends ObjectManagerActivity { @@ -35,17 +33,13 @@ public class ObjectEditor extends ObjectManagerActivity { UAVObject obj = objMngr.getObject(objectID, instID); Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); - TextView objectName = (TextView) findViewById(R.id.object_edit_name); - objectName.setText(obj.getName()); + ObjectEditView editView = (ObjectEditView) findViewById(R.id.object_edit_view); + editView.setName(obj.getName()); - LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); List fields = obj.getFields(); ListIterator li = fields.listIterator(); while(li.hasNext()) { - UAVObjectField field = li.next(); - TextView fieldName = new TextView(this); - fieldName.setText(field.getName()); - fieldViewList.addView(fieldName); + editView.addField(li.next()); } } From 38e4960fa5311e77bcfc4c0f25ae651202ac0ad7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 17:07:27 -0600 Subject: [PATCH 240/508] Update the project and checked in the meta data. Hopefully this will make it run more easily in future. --- androidgcs/.classpath | 8 +- androidgcs/.metadata/.lock | 0 androidgcs/.metadata/.log | 83 ++++ .../.metadata/.mylyn/repositories.xml.zip | Bin 0 -> 403 bytes androidgcs/.metadata/.mylyn/tasks.xml.zip | Bin 0 -> 250 bytes .../.plugins/org.eclipse.cdt.core/.log | 1 + .../.root/.indexes/history.version | 1 + .../.root/.indexes/properties.index | Bin 0 -> 57 bytes .../.root/.indexes/properties.version | 1 + .../org.eclipse.core.resources/.root/2.tree | Bin 0 -> 149 bytes .../.safetable/org.eclipse.core.resources | Bin 0 -> 614 bytes .../.settings/org.eclipse.cdt.ui.prefs | 5 + .../org.eclipse.core.resources.prefs | 3 + .../org.eclipse.epp.usagedata.recording.prefs | 3 + .../.settings/org.eclipse.jdt.ui.prefs | 15 + .../org.eclipse.mylyn.context.core.prefs | 3 + .../.settings/org.eclipse.team.cvs.ui.prefs | 3 + .../.settings/org.eclipse.team.ui.prefs | 3 + .../.settings/org.eclipse.ui.editors.prefs | 3 + .../.settings/org.eclipse.ui.ide.prefs | 5 + .../.settings/org.eclipse.ui.prefs | 3 + .../.settings/org.eclipse.ui.workbench.prefs | 3 + .../upload0.csv | 251 +++++++++++++ .../usagedata.csv | 83 ++++ .../org.eclipse.jdt.core/nonChainingJarsCache | Bin 0 -> 4 bytes .../variablesAndContainers.dat | Bin 0 -> 96 bytes .../org.eclipse.jdt.ui/OpenTypeHistory.xml | 2 + .../QualifiedTypeNameHistory.xml | 2 + .../org.eclipse.jdt.ui/dialog_settings.xml | 10 + .../org.eclipse.ui.ide/dialog_settings.xml | 9 + .../org.eclipse.ui.intro/dialog_settings.xml | 4 + .../dialog_settings.xml | 5 + .../org.eclipse.ui.workbench/workbench.xml | 355 ++++++++++++++++++ .../org.eclipse.ui.workbench/workingsets.xml | 4 + androidgcs/.metadata/version.ini | 1 + .../.settings/org.eclipse.jdt.core.prefs | 11 +- androidgcs/lint.xml | 3 + ...{default.properties => project.properties} | 4 +- 38 files changed, 879 insertions(+), 8 deletions(-) create mode 100644 androidgcs/.metadata/.lock create mode 100644 androidgcs/.metadata/.log create mode 100644 androidgcs/.metadata/.mylyn/repositories.xml.zip create mode 100644 androidgcs/.metadata/.mylyn/tasks.xml.zip create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/2.tree create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml create mode 100644 androidgcs/.metadata/version.ini create mode 100644 androidgcs/lint.xml rename androidgcs/{default.properties => project.properties} (72%) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 6f3f456df..eb33e4360 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,9 +1,9 @@ + - - - - + + + diff --git a/androidgcs/.metadata/.lock b/androidgcs/.metadata/.lock new file mode 100644 index 000000000..e69de29bb diff --git a/androidgcs/.metadata/.log b/androidgcs/.metadata/.log new file mode 100644 index 000000000..8955f7bbc --- /dev/null +++ b/androidgcs/.metadata/.log @@ -0,0 +1,83 @@ +!SESSION 2012-02-04 14:21:36.086 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 14:21:41.864 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences + +!ENTRY org.eclipse.ui.intro.universal 4 0 2012-02-04 14:21:44.892 +!MESSAGE /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) +!STACK 0 +java.io.FileNotFoundException: /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) + at java.io.FileInputStream.open(Native Method) + at java.io.FileInputStream.(FileInputStream.java:120) + at java.io.FileInputStream.(FileInputStream.java:79) + at sun.net.www.protocol.file.FileURLConnection.connect(FileURLConnection.java:70) + at sun.net.www.protocol.file.FileURLConnection.getInputStream(FileURLConnection.java:161) + at com.sun.org.apache.xerces.internal.impl.XMLEntityManager.setupCurrentEntity(XMLEntityManager.java:653) + at com.sun.org.apache.xerces.internal.impl.XMLVersionDetector.determineDocVersion(XMLVersionDetector.java:186) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:772) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:737) + at com.sun.org.apache.xerces.internal.parsers.XMLParser.parse(XMLParser.java:119) + at com.sun.org.apache.xerces.internal.parsers.DOMParser.parse(DOMParser.java:235) + at com.sun.org.apache.xerces.internal.jaxp.DocumentBuilderImpl.parse(DocumentBuilderImpl.java:284) + at javax.xml.parsers.DocumentBuilder.parse(DocumentBuilder.java:180) + at org.eclipse.ui.internal.intro.universal.IntroData.parse(IntroData.java:159) + at org.eclipse.ui.internal.intro.universal.IntroData.initialize(IntroData.java:63) + at org.eclipse.ui.internal.intro.universal.IntroData.(IntroData.java:47) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.loadData(CustomizationContentsArea.java:624) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.addPages(CustomizationContentsArea.java:489) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.createContents(CustomizationContentsArea.java:453) + at org.eclipse.ui.internal.intro.universal.CustomizationDialog.createDialogArea(CustomizationDialog.java:44) + at org.eclipse.jface.dialogs.Dialog.createContents(Dialog.java:760) + at org.eclipse.jface.window.Window.create(Window.java:431) + at org.eclipse.jface.dialogs.Dialog.create(Dialog.java:1089) + at org.eclipse.jface.window.Window.open(Window.java:790) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:35) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:29) + at org.eclipse.jface.action.Action.runWithEvent(Action.java:498) + at org.eclipse.jface.action.ActionContributionItem.handleWidgetSelection(ActionContributionItem.java:584) + at org.eclipse.jface.action.ActionContributionItem.access$2(ActionContributionItem.java:501) + at org.eclipse.jface.action.ActionContributionItem$6.handleEvent(ActionContributionItem.java:452) + at org.eclipse.swt.widgets.EventTable.sendEvent(EventTable.java:84) + at org.eclipse.swt.widgets.Display.sendEvent(Display.java:3543) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1250) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1273) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1258) + at org.eclipse.swt.widgets.Widget.notifyListeners(Widget.java:1079) + at org.eclipse.swt.widgets.Display.runDeferredEvents(Display.java:3441) + at org.eclipse.swt.widgets.Display.readAndDispatch(Display.java:3100) + at org.eclipse.ui.internal.Workbench.runEventLoop(Workbench.java:2405) + at org.eclipse.ui.internal.Workbench.runUI(Workbench.java:2369) + at org.eclipse.ui.internal.Workbench.access$4(Workbench.java:2221) + at org.eclipse.ui.internal.Workbench$5.run(Workbench.java:500) + at org.eclipse.core.databinding.observable.Realm.runWithDefault(Realm.java:332) + at org.eclipse.ui.internal.Workbench.createAndRunWorkbench(Workbench.java:493) + at org.eclipse.ui.PlatformUI.createAndRunWorkbench(PlatformUI.java:149) + at org.eclipse.ui.internal.ide.application.IDEApplication.start(IDEApplication.java:113) + at org.eclipse.equinox.internal.app.EclipseAppHandle.run(EclipseAppHandle.java:194) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.runApplication(EclipseAppLauncher.java:110) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.start(EclipseAppLauncher.java:79) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:368) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:179) + at sun.reflect.NativeMethodAccessorImpl.invoke0(Native Method) + at sun.reflect.NativeMethodAccessorImpl.invoke(NativeMethodAccessorImpl.java:39) + at sun.reflect.DelegatingMethodAccessorImpl.invoke(DelegatingMethodAccessorImpl.java:25) + at java.lang.reflect.Method.invoke(Method.java:597) + at org.eclipse.equinox.launcher.Main.invokeFramework(Main.java:559) + at org.eclipse.equinox.launcher.Main.basicRun(Main.java:514) + at org.eclipse.equinox.launcher.Main.run(Main.java:1311) +!SESSION 2012-02-04 15:23:30.048 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 15:23:34.575 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences diff --git a/androidgcs/.metadata/.mylyn/repositories.xml.zip b/androidgcs/.metadata/.mylyn/repositories.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..e4df3bd3582f499f1a60b5def214b8ff52af6617 GIT binary patch literal 403 zcmWIWW@Zs#-~hsBMJ^5uNI(F{E=n!PFU~Bdj(; zVVO}bA}k9RU9H|_{jM!-va0dQyZ@?^bz^fywc_@+7(B7PS7R*c8`dl8&6Bbx*kFpf z!UfTNChLMenCzB(Vj$U{HcO2EMwQWWeBm$C<8L3AOn9FDyjhXMjCb8$XV&SwY{4(ytny2L z>Zr1KZsz5i=REypu2G!!Fu39-+x}N6Dmous-A{8_xY)$`S9N}$_2O##r|q}OnXHQb zs!#4`+gH4ys;~2NX}{PedAH=+g>TFBZddPTZ;$@K|4-sWx%33i%5DEskL3q=vvV9^ w68pi($iR@z%)k)f&B!FefCxZjIZyzi0`%Yv@MdKLsbB;`J0NWjG?jq?0GoN09smFU literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.mylyn/tasks.xml.zip b/androidgcs/.metadata/.mylyn/tasks.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..2c8620af394508c77be5ef0f6f867a56804938c0 GIT binary patch literal 250 zcmWIWW@Zs#-~dAIY8M9vB)|h?mn0Tv=VTU_=vCzAY~Hy3#MwX%Z(Xf(XU=a9HM(LP z5ae;z`<(yDGv3=nxp)gNZw(02(DOXw?RnEr%s1&+P<07Q|H{blRA2V9L+CH zm|nGXSgTK4vh2Bds8$6-=~ITSEzeY)TZ~o*1y2$ABUEh2^7U=bm&CMNj0^$Z>>R?m rvc?5KcT54|0B=Sn5e9@?k>x;cMFq$%5AbGX1IaQ1p%su`1y%|G7vM-E literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log new file mode 100644 index 000000000..bce672614 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log @@ -0,0 +1 @@ +*** SESSION Feb 04, 2012 14:21:39.72 ------------------------------------------- diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version new file mode 100644 index 000000000..25cb955ba --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version @@ -0,0 +1 @@ + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index new file mode 100644 index 0000000000000000000000000000000000000000..9c245ea2cfab3511d0f8b7802966a5b2bb67b287 GIT binary patch literal 57 zcmZQ%U|?WmVAN+|WMUA>FG|--P0q4Yy oITE#s5Hp-2#a#t%!FeA{J(nSSiHf?N|MotxHB4MgVOxlqE}m~5?f?J) literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources new file mode 100644 index 0000000000000000000000000000000000000000..f783b188fb03e942944121a16ffc8983afa430df GIT binary patch literal 614 zcmZ?R*xjhShe1S2b=vdAllRFf=Oz}Hq!uZZBqrsgaw!KVmMFNTCMg)0C>WYr8JPf) zf^%?)f{}rt5m$0fYGRQ~YEDUFe11{7UTShqWs%=_gPH`$%3P^!# zML}j!Vo7Fx9*WW|m{LPyBMW0o12Z!d14Bc+THvNbwU}6#8UwZ9a0}c5h+A-|%B{?) w%+o7LEY2?0E6s$uTVJoFC^gmAi0eSa@6X^M3jEwty}SIF!)TDD>X8;?0Hs9PH2?qr literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs new file mode 100644 index 000000000..3f144b036 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +spelling_locale_initialized=true +useAnnotationsPrefPage=true +eclipse.preferences.version=1 +useQuickDiffPrefPage=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs new file mode 100644 index 000000000..360fc96b9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +version=1 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs new file mode 100644 index 000000000..87706c344 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:44 CST 2012 +org.eclipse.epp.usagedata.recording.last-upload=1328386904231 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs new file mode 100644 index 000000000..bdcfb11b5 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs @@ -0,0 +1,15 @@ +#Sat Feb 04 15:21:25 CST 2012 +useQuickDiffPrefPage=true +proposalOrderMigrated=true +tabWidthPropagated=true +content_assist_proposals_background=255,255,255 +org.eclipse.jdt.ui.javadoclocations.migrated=true +useAnnotationsPrefPage=true +org.eclipse.jface.textfont=1|Monaco|11.0|0|COCOA|1|; +org.eclipse.jdt.internal.ui.navigator.layout=2 +org.eclipse.jdt.ui.editor.tab.width= +org.eclipse.jdt.ui.formatterprofiles.version=11 +spelling_locale_initialized=true +eclipse.preferences.version=1 +content_assist_proposals_foreground=0,0,0 +fontPropagated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs new file mode 100644 index 000000000..7ea301b2d --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +mylyn.attention.migrated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs new file mode 100644 index 000000000..62dee9f90 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +pref_first_startup=false +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs new file mode 100644 index 000000000..06b301613 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +org.eclipse.team.ui.first_time=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs new file mode 100644 index 000000000..90e1e2da9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +overviewRuler_migration=migrated_3.1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs new file mode 100644 index 000000000..b945f2889 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +tipsAndTricks=true +platformState=1328386704250 +PROBLEMS_FILTERS_MIGRATE=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs new file mode 100644 index 000000000..a97c1c1ab --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +showIntro=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs new file mode 100644 index 000000000..005c5e9bc --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +ENABLED_DECORATORS=com.android.ide.eclipse.adt.project.FolderDecorator\:true,org.eclipse.cdt.ui.indexedFiles\:false,org.eclipse.jdt.ui.override.decorator\:true,org.eclipse.jdt.ui.interface.decorator\:false,org.eclipse.jdt.ui.buildpath.decorator\:true,org.eclipse.mylyn.context.ui.decorator.interest\:true,org.eclipse.mylyn.tasks.ui.decorators.task\:true,org.eclipse.mylyn.team.ui.changeset.decorator\:true,org.eclipse.team.cvs.ui.decorator\:true,org.eclipse.ui.LinkedResourceDecorator\:true,org.eclipse.ui.ContentTypeDecorator\:true, diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv new file mode 100644 index 000000000..bc6540615 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv @@ -0,0 +1,251 @@ +what,kind,bundleId,bundleVersion,description,time +activated,perspective,org.eclipse.cdt.ui,,"org.eclipse.cdt.ui.CPerspective",1328386903139 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328386903141 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328386903142 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328386903143 +started,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328386903143 +started,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328386903144 +started,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328386903147 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328386903148 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328386903148 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328386903149 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328386903149 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328386903150 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328386903151 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328386903152 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328386903153 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328386903153 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328386903154 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328386903154 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328386903155 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328386903155 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328386903156 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328386903157 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328386903158 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328386903159 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328386903161 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328386903164 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328386903165 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328386903166 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328386903167 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328386903168 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328386903168 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328386903169 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328386903169 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328386903171 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328386903171 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328386903172 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328386903172 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328386903172 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328386903175 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328386903176 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328386903177 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328386903177 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328386903178 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328386903179 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328386903179 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328386903180 +started,bundle,org.eclipse.ltk.core.refactoring,3.5.0.v20090513-2000,"org.eclipse.ltk.core.refactoring",1328386903180 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328386903181 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328386903181 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328386903182 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328386903183 +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328386903183 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328386903184 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328386903185 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328386903186 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328386903186 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328386903187 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328386903188 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328386903189 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328386903189 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328386903191 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328386903191 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328386903195 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328386903196 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328386903198 +started,bundle,org.eclipse.ui.intro,3.3.2.v20100111_35x,"org.eclipse.ui.intro",1328386903198 +started,bundle,org.eclipse.ui.intro.universal,3.2.300.v20090526,"org.eclipse.ui.intro.universal",1328386903198 +started,bundle,org.eclipse.ui.navigator,3.4.2.M20100120-0800,"org.eclipse.ui.navigator",1328386903199 +started,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328386903200 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328386903200 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328386903201 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328386903202 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328386903203 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328386903207 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328386903209 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328386903210 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328386903211 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328386903212 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328386903218 +os,sysinfo,,,"macosx",1328386903226 +arch,sysinfo,,,"x86_64",1328386903226 +ws,sysinfo,,,"cocoa",1328386903226 +locale,sysinfo,,,"en_US",1328386903226 +processors,sysinfo,,,"4",1328386903226 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328386903226 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328386903227 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328386903227 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.specification.version,sysinfo,,,"1.6",1328386903227 +java.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.version,sysinfo,,,"1.6.0_29",1328386903227 +java.vm.info,sysinfo,,,"mixed mode",1328386903227 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328386903227 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328386903227 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.vm.specification.version,sysinfo,,,"1.0",1328386903227 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.vm.version,sysinfo,,,"20.4-b02-402",1328386903227 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328386903389 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328386903414 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328386903450 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328386903464 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386903480 +activated,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386903487 +error,log,,,"/Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory)",1328386904897 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386905209 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386906797 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328386912464 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912583 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912596 +closed,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386912607 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328386912856 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328386912895 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386920116 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387108087 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387114332 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387670491 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387680147 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389984496 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389985341 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390196855 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390210754 +started,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390214192 +started,bundle,org.eclipse.wst.sse.core,1.1.402.v201001251516,"org.eclipse.wst.sse.core",1328390214246 +started,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390214248 +started,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390214467 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390455517 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390462855 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390470613 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.PackageExplorer",1328390470944 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390471037 +opened,view,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui.views.tasks",1328390471127 +activated,perspective,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavaPerspective",1328390471151 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390471175 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474490 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474500 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475141 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475161 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390475451 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390475842 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390485206 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390485703 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390485705 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390485706 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390485707 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390485707 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390485708 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390485709 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390485709 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390485710 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390485710 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390485712 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390485713 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390485714 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.tasks.bugs,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.bugs",1328390485717 +stopped,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390485719 +stopped,bundle,org.eclipse.ant.ui,3.4.2.v20091204_r352,"org.eclipse.ant.ui",1328390485719 +stopped,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390485719 +stopped,bundle,org.eclipse.jdt.junit,3.5.2.r352_v20100113-0800,"org.eclipse.jdt.junit",1328390485720 +stopped,bundle,org.eclipse.jdt.debug.ui,3.4.1.v20090811_r351,"org.eclipse.jdt.debug.ui",1328390485721 +stopped,bundle,org.eclipse.jdt.apt.ui,3.3.200.v20090930-2100_R35x,"org.eclipse.jdt.apt.ui",1328390485722 +stopped,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390485726 +stopped,bundle,org.eclipse.wst.dtd.ui,1.0.400.v200904300717,"org.eclipse.wst.dtd.ui",1328390485730 +stopped,bundle,org.eclipse.wst.xsd.ui,1.2.204.v200909021537,"org.eclipse.wst.xsd.ui",1328390485747 +stopped,bundle,org.eclipse.wst.xml.ui,1.1.2.v201001222130,"org.eclipse.wst.xml.ui",1328390485747 +stopped,bundle,org.eclipse.wst.common.ui,1.1.402.v200901262305,"org.eclipse.wst.common.ui",1328390485748 +stopped,bundle,org.eclipse.wst.sse.ui,1.1.102.v200910200227,"org.eclipse.wst.sse.ui",1328390485749 +stopped,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390485750 +stopped,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390485750 +stopped,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390485751 +stopped,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390485751 +stopped,bundle,org.eclipse.compare,3.5.2.r35x_20100113-0800,"org.eclipse.compare",1328390485752 +stopped,bundle,org.eclipse.ui.externaltools,3.2.0.v20090504,"org.eclipse.ui.externaltools",1328390485753 +stopped,bundle,org.eclipse.debug.ui,3.5.2.v20091028_r352,"org.eclipse.debug.ui",1328390485756 +stopped,bundle,org.eclipse.mylyn.wikitext.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.ui",1328390485757 +stopped,bundle,com.android.ide.eclipse.hierarchyviewer,10.0.1.v201103111512-110841,"com.android.ide.eclipse.hierarchyviewer",1328390485757 +stopped,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390485757 +stopped,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390485757 +stopped,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390485757 +stopped,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390485758 +stopped,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328390485758 +activated,perspective,org.eclipse.jdt.ui,,"org.eclipse.jdt.ui.JavaPerspective",1328390616647 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328390616648 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328390616653 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328390616654 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328390616654 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328390616655 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328390616656 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328390616656 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328390616656 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328390616657 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328390616658 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328390616660 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328390616660 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328390616661 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328390616662 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328390616663 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328390616663 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328390616664 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328390616668 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328390616676 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328390616676 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328390616677 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328390616679 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328390616680 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328390616681 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328390616682 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328390616688 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328390616689 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328390616690 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328390616691 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328390616692 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328390616692 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328390616693 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328390616693 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328390616694 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328390616695 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328390616695 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328390616696 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328390616697 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328390616697 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328390616698 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328390616698 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328390616699 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390616706 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328390616706 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390616707 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv new file mode 100644 index 000000000..510c72478 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv @@ -0,0 +1,83 @@ +what,kind,bundleId,bundleVersion,description,time +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328390616707 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390616708 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328390616708 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390616709 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390616710 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390616711 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328390616712 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328390616712 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390616713 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390616714 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328390616715 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390616716 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390616717 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328390616717 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328390616718 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328390616719 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328390616720 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328390616720 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328390616721 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328390616722 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328390616722 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328390616723 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328390616724 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328390616725 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390616730 +os,sysinfo,,,"macosx",1328390616740 +arch,sysinfo,,,"x86_64",1328390616740 +ws,sysinfo,,,"cocoa",1328390616740 +locale,sysinfo,,,"en_US",1328390616740 +processors,sysinfo,,,"4",1328390616740 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328390616740 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328390616740 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328390616740 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.specification.version,sysinfo,,,"1.6",1328390616740 +java.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.version,sysinfo,,,"1.6.0_29",1328390616740 +java.vm.info,sysinfo,,,"mixed mode",1328390616740 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328390616740 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328390616740 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.vm.specification.version,sysinfo,,,"1.0",1328390616740 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.vm.version,sysinfo,,,"20.4-b02-402",1328390616740 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328390616768 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328390616783 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328390616808 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328390616820 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390619481 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328390623001 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328390623371 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328390623409 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328390630622 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390659248 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.file.import",1328390659277 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390663881 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390664441 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390664444 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390664445 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390664447 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390664448 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390664449 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390664452 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390664453 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390664454 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390664455 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390664455 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390664458 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390664459 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390664462 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390664462 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache new file mode 100644 index 0000000000000000000000000000000000000000..593f4708db84ac8fd0f5cc47c634f38c013fe9e4 GIT binary patch literal 4 LcmZQzU|;|M00aO5 literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat new file mode 100644 index 0000000000000000000000000000000000000000..3aea61cb8e5c86745251f85e5305774c8841c019 GIT binary patch literal 96 zcmZQzU|?c^09G)??iJ)39~|V&2;?y`aCwFLd4|M$`1`to1eh4Oq0&MA{vjX{W(KeZ SA5SL`kA;B`q5)_CL=yl}T@PLW literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml new file mode 100644 index 000000000..a4ee3cbc9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml new file mode 100644 index 000000000..9e390f501 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml new file mode 100644 index 000000000..8bc608925 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml @@ -0,0 +1,10 @@ + +
+
+ + + + + +
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml new file mode 100644 index 000000000..ab9bf177c --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml @@ -0,0 +1,9 @@ + +
+
+ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml new file mode 100644 index 000000000..f118f0213 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml @@ -0,0 +1,4 @@ + +
+ +
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml new file mode 100644 index 000000000..5b583c4be --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml @@ -0,0 +1,5 @@ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml new file mode 100644 index 000000000..931fd0157 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml @@ -0,0 +1,355 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml new file mode 100644 index 000000000..8daaf65a1 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/version.ini b/androidgcs/.metadata/version.ini new file mode 100644 index 000000000..c51ff745b --- /dev/null +++ b/androidgcs/.metadata/version.ini @@ -0,0 +1 @@ +org.eclipse.core.runtime=1 \ No newline at end of file diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs index f3fe4d6d6..a149e8e84 100644 --- a/androidgcs/.settings/org.eclipse.jdt.core.prefs +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -1,5 +1,12 @@ -#Tue Mar 01 01:16:25 CST 2011 +#Sat Feb 04 16:05:48 CST 2012 eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.inlineJsrBytecode=enabled org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 -org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.codegen.unusedLocal=preserve +org.eclipse.jdt.core.compiler.compliance=1.6 +org.eclipse.jdt.core.compiler.debug.lineNumber=generate +org.eclipse.jdt.core.compiler.debug.localVariable=generate +org.eclipse.jdt.core.compiler.debug.sourceFile=generate +org.eclipse.jdt.core.compiler.problem.assertIdentifier=error +org.eclipse.jdt.core.compiler.problem.enumIdentifier=error org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/lint.xml b/androidgcs/lint.xml new file mode 100644 index 000000000..ee0eead5b --- /dev/null +++ b/androidgcs/lint.xml @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/project.properties similarity index 72% rename from androidgcs/default.properties rename to androidgcs/project.properties index fd1cedd24..5d85d779c 100644 --- a/androidgcs/default.properties +++ b/androidgcs/project.properties @@ -4,8 +4,8 @@ # This file must be checked in Version Control Systems. # # To customize properties used by the Ant build system use, -# "build.properties", and override values to adapt the script to your +# "ant.properties", and override values to adapt the script to your # project structure. # Project target. -target=Google Inc.:Google APIs:10 +target=Google Inc.:Google APIs:13 From 739dc0f9841c8afb737d892e025956ecd7cfb3de Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 18:30:04 -0600 Subject: [PATCH 241/508] Update the UAVObjects to the version on next. At some point a make script should generate these and copy from build/uavobjects-synth/java to this directory automatically. Also make sure java objects use CamelCase --- .../uavtalk/uavobjects/AHRSCalibration.java | 51 +- .../uavtalk/uavobjects/AHRSSettings.java | 32 +- .../uavtalk/uavobjects/AccessoryDesired.java | 139 +++++ .../uavtalk/uavobjects/ActuatorCommand.java | 12 +- .../uavtalk/uavobjects/ActuatorDesired.java | 2 +- .../uavtalk/uavobjects/ActuatorSettings.java | 496 ++++++++++-------- .../uavtalk/uavobjects/AhrsStatus.java | 10 +- .../uavtalk/uavobjects/AttitudeActual.java | 4 +- .../uavtalk/uavobjects/AttitudeRaw.java | 24 +- .../uavtalk/uavobjects/AttitudeSettings.java | 68 ++- .../uavtalk/uavobjects/BaroAltitude.java | 2 +- .../uavtalk/uavobjects/CameraDesired.java | 147 ++++++ .../uavobjects/CameraStabSettings.java | 205 ++++++++ ...emetrySettings.java => FaultSettings.java} | 45 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 97 +--- .../uavobjects/FlightBatterySettings.java | 177 +++++++ .../uavobjects/FlightBatteryState.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavobjects/FlightPlanSettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 35 +- .../uavtalk/uavobjects/FlightStatus.java | 155 ++++++ .../uavobjects/FlightTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GCSReceiver.java | 144 +++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GPSPosition.java | 28 +- .../uavtalk/uavobjects/GPSSatellites.java | 48 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 10 +- .../uavtalk/uavobjects/GuidanceSettings.java | 76 +-- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 291 ++++++++++ .../uavtalk/uavobjects/I2CStats.java | 34 +- .../uavobjects/ManualControlCommand.java | 55 +- .../uavobjects/ManualControlSettings.java | 313 +++++------ .../uavtalk/uavobjects/MixerSettings.java | 161 +++++- .../uavtalk/uavobjects/MixerStatus.java | 2 +- .../uavtalk/uavobjects/NedAccel.java | 2 +- .../uavtalk/uavobjects/ObjectPersistence.java | 23 +- .../uavtalk/uavobjects/PositionActual.java | 2 +- .../uavtalk/uavobjects/PositionDesired.java | 2 +- .../uavtalk/uavobjects/RateDesired.java | 2 +- ...erySettings.java => ReceiverActivity.java} | 74 ++- .../uavtalk/uavobjects/SonarAltitude.java | 2 +- .../uavobjects/StabilizationDesired.java | 4 +- .../uavobjects/StabilizationSettings.java | 119 +++-- .../uavtalk/uavobjects/SystemAlarms.java | 8 +- .../uavtalk/uavobjects/SystemSettings.java | 9 +- .../uavtalk/uavobjects/SystemStats.java | 6 +- .../uavtalk/uavobjects/TaskInfo.java | 24 +- .../uavobjects/UAVObjectsInitialize.java | 13 +- .../uavtalk/uavobjects/VelocityActual.java | 2 +- .../uavtalk/uavobjects/VelocityDesired.java | 2 +- .../uavtalk/uavobjects/WatchdogStatus.java | 2 +- .../java/uavobjectgeneratorjava.cpp | 2 +- 53 files changed, 2363 insertions(+), 867 deletions(-) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{TelemetrySettings.java => FaultSettings.java} (74%) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{BatterySettings.java => ReceiverActivity.java} (61%) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index 922582398..47d42991e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -51,30 +51,29 @@ public class AHRSCalibration extends UAVDataObject { List fields = new ArrayList(); - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - List accel_biasElemNames = new ArrayList(); accel_biasElemNames.add("X"); accel_biasElemNames.add("Y"); accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); List accel_scaleElemNames = new ArrayList(); accel_scaleElemNames.add("X"); accel_scaleElemNames.add("Y"); accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_orthoElemNames = new ArrayList(); + accel_orthoElemNames.add("XY"); + accel_orthoElemNames.add("XZ"); + accel_orthoElemNames.add("YZ"); + fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); List accel_varElemNames = new ArrayList(); accel_varElemNames.add("X"); accel_varElemNames.add("Y"); accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); List gyro_biasElemNames = new ArrayList(); gyro_biasElemNames.add("X"); @@ -126,6 +125,13 @@ public class AHRSCalibration extends UAVDataObject { pos_varElemNames.add("0"); fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -171,19 +177,21 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); getField("accel_scale").setValue(0.0359,0); getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(-0.0359,2); + getField("accel_scale").setValue(0.0359,2); + getField("accel_ortho").setValue(0,0); + getField("accel_ortho").setValue(0,1); + getField("accel_ortho").setValue(0,2); getField("accel_var").setValue(0.0005,0); getField("accel_var").setValue(0.0005,1); getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(23,0); - getField("gyro_bias").setValue(-23,1); - getField("gyro_bias").setValue(23,2); + getField("gyro_bias").setValue(28,0); + getField("gyro_bias").setValue(-28,1); + getField("gyro_bias").setValue(28,2); getField("gyro_scale").setValue(-0.017,0); getField("gyro_scale").setValue(0.017,1); getField("gyro_scale").setValue(-0.017,2); @@ -196,14 +204,15 @@ public class AHRSCalibration extends UAVDataObject { getField("mag_bias").setValue(0,0); getField("mag_bias").setValue(0,1); getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(-2,0); - getField("mag_scale").setValue(-2,1); - getField("mag_scale").setValue(-2,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); getField("mag_var").setValue(50,0); getField("mag_var").setValue(50,1); getField("mag_var").setValue(50,2); - getField("vel_var").setValue(0.4); - getField("pos_var").setValue(0.4); + getField("vel_var").setValue(10); + getField("pos_var").setValue(0.04); + getField("measure_var").setValue("SET"); } @@ -232,7 +241,7 @@ public class AHRSCalibration extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30101BB2; + protected static final int OBJID = 0xFD0EDFC4; protected static final String NAME = "AHRSCalibration"; protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index c49c04778..032dae775 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -51,6 +51,18 @@ public class AHRSSettings extends UAVDataObject { List fields = new ArrayList(); + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + List AlgorithmElemNames = new ArrayList(); AlgorithmElemNames.add("0"); List AlgorithmEnumOptions = new ArrayList(); @@ -75,18 +87,6 @@ public class AHRSSettings extends UAVDataObject { BiasCorrectedRawEnumOptions.add("FALSE"); fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -132,13 +132,13 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); getField("BiasCorrectedRaw").setValue("TRUE"); - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); } @@ -167,7 +167,7 @@ public class AHRSSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDEFC5548; + protected static final int OBJID = 0xF8591ED8; protected static final String NAME = "AHRSSettings"; protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java new file mode 100644 index 000000000..13c63dfdd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + +generated from accessorydesired.xml + **/ +public class AccessoryDesired extends UAVDataObject { + + public AccessoryDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccessoryValElemNames = new ArrayList(); + AccessoryValElemNames.add("0"); + fields.add( new UAVObjectField("AccessoryVal", "", UAVObjectField.FieldType.FLOAT32, AccessoryValElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AccessoryDesired obj = new AccessoryDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AccessoryDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AccessoryDesired)(objMngr.getObject(AccessoryDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xC409985A; + protected static final String NAME = "AccessoryDesired"; + protected static String DESCRIPTION = "Desired Auxillary actuator settings. Comes from @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index a5d6230ac..08f2ebefe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -60,16 +60,18 @@ public class ActuatorCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); + ChannelElemNames.add("9"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); - List UpdateTimeElemNames = new ArrayList(); - UpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); - List MaxUpdateTimeElemNames = new ArrayList(); MaxUpdateTimeElemNames.add("0"); fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + List NumFailedUpdatesElemNames = new ArrayList(); NumFailedUpdatesElemNames.add("0"); fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); @@ -147,7 +149,7 @@ public class ActuatorCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE8E077D8; + protected static final int OBJID = 0x5324CB8; protected static final String NAME = "ActuatorCommand"; protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index b81ca29da..03ff1985c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -148,7 +148,7 @@ public class ActuatorDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD4516782; + protected static final int OBJID = 0xCA4BC4A4; protected static final String NAME = "ActuatorDesired"; protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 542b433d1..71b0bb49f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -51,202 +51,6 @@ public class ActuatorSettings extends UAVDataObject { List fields = new ArrayList(); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYawElemNames = new ArrayList(); - FixedWingYawElemNames.add("0"); - List FixedWingYawEnumOptions = new ArrayList(); - FixedWingYawEnumOptions.add("Channel1"); - FixedWingYawEnumOptions.add("Channel2"); - FixedWingYawEnumOptions.add("Channel3"); - FixedWingYawEnumOptions.add("Channel4"); - FixedWingYawEnumOptions.add("Channel5"); - FixedWingYawEnumOptions.add("Channel6"); - FixedWingYawEnumOptions.add("Channel7"); - FixedWingYawEnumOptions.add("Channel8"); - FixedWingYawEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelUpdateFreqElemNames = new ArrayList(); ChannelUpdateFreqElemNames.add("0"); ChannelUpdateFreqElemNames.add("1"); @@ -263,6 +67,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelMaxElemNames.add("5"); ChannelMaxElemNames.add("6"); ChannelMaxElemNames.add("7"); + ChannelMaxElemNames.add("8"); + ChannelMaxElemNames.add("9"); fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); List ChannelNeutralElemNames = new ArrayList(); @@ -274,6 +80,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelNeutralElemNames.add("5"); ChannelNeutralElemNames.add("6"); ChannelNeutralElemNames.add("7"); + ChannelNeutralElemNames.add("8"); + ChannelNeutralElemNames.add("9"); fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); List ChannelMinElemNames = new ArrayList(); @@ -285,8 +93,250 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("5"); ChannelMinElemNames.add("6"); ChannelMinElemNames.add("7"); + ChannelMinElemNames.add("8"); + ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("Channel9"); + FixedWingRoll1EnumOptions.add("Channel10"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("Channel9"); + FixedWingRoll2EnumOptions.add("Channel10"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("Channel9"); + FixedWingPitch1EnumOptions.add("Channel10"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("Channel9"); + FixedWingPitch2EnumOptions.add("Channel10"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYaw1ElemNames = new ArrayList(); + FixedWingYaw1ElemNames.add("0"); + List FixedWingYaw1EnumOptions = new ArrayList(); + FixedWingYaw1EnumOptions.add("Channel1"); + FixedWingYaw1EnumOptions.add("Channel2"); + FixedWingYaw1EnumOptions.add("Channel3"); + FixedWingYaw1EnumOptions.add("Channel4"); + FixedWingYaw1EnumOptions.add("Channel5"); + FixedWingYaw1EnumOptions.add("Channel6"); + FixedWingYaw1EnumOptions.add("Channel7"); + FixedWingYaw1EnumOptions.add("Channel8"); + FixedWingYaw1EnumOptions.add("Channel9"); + FixedWingYaw1EnumOptions.add("Channel10"); + FixedWingYaw1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); + + List FixedWingYaw2ElemNames = new ArrayList(); + FixedWingYaw2ElemNames.add("0"); + List FixedWingYaw2EnumOptions = new ArrayList(); + FixedWingYaw2EnumOptions.add("Channel1"); + FixedWingYaw2EnumOptions.add("Channel2"); + FixedWingYaw2EnumOptions.add("Channel3"); + FixedWingYaw2EnumOptions.add("Channel4"); + FixedWingYaw2EnumOptions.add("Channel5"); + FixedWingYaw2EnumOptions.add("Channel6"); + FixedWingYaw2EnumOptions.add("Channel7"); + FixedWingYaw2EnumOptions.add("Channel8"); + FixedWingYaw2EnumOptions.add("Channel9"); + FixedWingYaw2EnumOptions.add("Channel10"); + FixedWingYaw2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("Channel9"); + FixedWingThrottleEnumOptions.add("Channel10"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("Channel9"); + VTOLMotorNEnumOptions.add("Channel10"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("Channel9"); + VTOLMotorNEEnumOptions.add("Channel10"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("Channel9"); + VTOLMotorEEnumOptions.add("Channel10"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("Channel9"); + VTOLMotorSEEnumOptions.add("Channel10"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("Channel9"); + VTOLMotorSEnumOptions.add("Channel10"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("Channel9"); + VTOLMotorSWEnumOptions.add("Channel10"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("Channel9"); + VTOLMotorWEnumOptions.add("Channel10"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("Channel9"); + VTOLMotorNWEnumOptions.add("Channel10"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -296,10 +346,13 @@ public class ActuatorSettings extends UAVDataObject { ChannelTypeElemNames.add("5"); ChannelTypeElemNames.add("6"); ChannelTypeElemNames.add("7"); + ChannelTypeElemNames.add("8"); + ChannelTypeElemNames.add("9"); List ChannelTypeEnumOptions = new ArrayList(); ChannelTypeEnumOptions.add("PWM"); ChannelTypeEnumOptions.add("MK"); ChannelTypeEnumOptions.add("ASTEC4"); + ChannelTypeEnumOptions.add("PWM Alarm Buzzer"); fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); List ChannelAddrElemNames = new ArrayList(); @@ -311,8 +364,17 @@ public class ActuatorSettings extends UAVDataObject { ChannelAddrElemNames.add("5"); ChannelAddrElemNames.add("6"); ChannelAddrElemNames.add("7"); + ChannelAddrElemNames.add("8"); + ChannelAddrElemNames.add("9"); fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + List MotorsSpinWhileArmedElemNames = new ArrayList(); + MotorsSpinWhileArmedElemNames.add("0"); + List MotorsSpinWhileArmedEnumOptions = new ArrayList(); + MotorsSpinWhileArmedEnumOptions.add("FALSE"); + MotorsSpinWhileArmedEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("MotorsSpinWhileArmed", "", UAVObjectField.FieldType.ENUM, MotorsSpinWhileArmedElemNames, MotorsSpinWhileArmedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -358,20 +420,6 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -384,6 +432,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMax").setValue(1000,5); getField("ChannelMax").setValue(1000,6); getField("ChannelMax").setValue(1000,7); + getField("ChannelMax").setValue(1000,8); + getField("ChannelMax").setValue(1000,9); getField("ChannelNeutral").setValue(1000,0); getField("ChannelNeutral").setValue(1000,1); getField("ChannelNeutral").setValue(1000,2); @@ -392,6 +442,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelNeutral").setValue(1000,5); getField("ChannelNeutral").setValue(1000,6); getField("ChannelNeutral").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,8); + getField("ChannelNeutral").setValue(1000,9); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -400,6 +452,23 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelMin").setValue(1000,9); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw1").setValue("None"); + getField("FixedWingYaw2").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -408,6 +477,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelType").setValue("PWM",5); getField("ChannelType").setValue("PWM",6); getField("ChannelType").setValue("PWM",7); + getField("ChannelType").setValue("PWM",8); + getField("ChannelType").setValue("PWM",9); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); @@ -416,6 +487,9 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelAddr").setValue(5,5); getField("ChannelAddr").setValue(6,6); getField("ChannelAddr").setValue(7,7); + getField("ChannelAddr").setValue(8,8); + getField("ChannelAddr").setValue(9,9); + getField("MotorsSpinWhileArmed").setValue("FALSE"); } @@ -444,7 +518,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1BF864C2; + protected static final int OBJID = 0xF2875746; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java index 3ee8304ae..82e447a70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -51,6 +51,10 @@ public class AhrsStatus extends UAVDataObject { List fields = new ArrayList(); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + List SerialNumberElemNames = new ArrayList(); SerialNumberElemNames.add("0"); SerialNumberElemNames.add("1"); @@ -66,10 +70,6 @@ public class AhrsStatus extends UAVDataObject { CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - List IdleTimePerCyleElemNames = new ArrayList(); IdleTimePerCyleElemNames.add("0"); fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); @@ -190,7 +190,7 @@ public class AhrsStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37A5F7A2; + protected static final int OBJID = 0x706D1AB8; protected static final String NAME = "AhrsStatus"; protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 714c18571..7c9272cad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -110,7 +110,7 @@ public class AttitudeActual extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 500; + metadata.flightTelemetryUpdatePeriod = 100; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; metadata.loggingUpdatePeriod = 0; @@ -152,7 +152,7 @@ public class AttitudeActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xFC5B8CF4; + protected static final int OBJID = 0x33DAD5E6; protected static final String NAME = "AttitudeActual"; protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java index d28302b6a..b8c3aacb4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -51,29 +51,29 @@ public class AttitudeRaw extends UAVDataObject { List fields = new ArrayList(); - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - List gyrosElemNames = new ArrayList(); gyrosElemNames.add("X"); gyrosElemNames.add("Y"); gyrosElemNames.add("Z"); fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - List accelsElemNames = new ArrayList(); accelsElemNames.add("X"); accelsElemNames.add("Y"); accelsElemNames.add("Z"); fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -147,7 +147,7 @@ public class AttitudeRaw extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37747DE6; + protected static final int OBJID = 0xDB722974; protected static final String NAME = "AttitudeRaw"; protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 482fc12ce..3034a99ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -51,12 +51,6 @@ public class AttitudeSettings extends UAVDataObject { List fields = new ArrayList(); - List AccelBiasElemNames = new ArrayList(); - AccelBiasElemNames.add("X"); - AccelBiasElemNames.add("Y"); - AccelBiasElemNames.add("Z"); - fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); - List GyroGainElemNames = new ArrayList(); GyroGainElemNames.add("0"); fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); @@ -69,6 +63,50 @@ public class AttitudeSettings extends UAVDataObject { AccelKiElemNames.add("0"); fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + List YawBiasRateElemNames = new ArrayList(); + YawBiasRateElemNames.add("0"); + fields.add( new UAVObjectField("YawBiasRate", "channel", UAVObjectField.FieldType.FLOAT32, YawBiasRateElemNames, null) ); + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroBiasElemNames = new ArrayList(); + GyroBiasElemNames.add("X"); + GyroBiasElemNames.add("Y"); + GyroBiasElemNames.add("Z"); + fields.add( new UAVObjectField("GyroBias", "deg/s * 100", UAVObjectField.FieldType.INT16, GyroBiasElemNames, null) ); + + List BoardRotationElemNames = new ArrayList(); + BoardRotationElemNames.add("Roll"); + BoardRotationElemNames.add("Pitch"); + BoardRotationElemNames.add("Yaw"); + fields.add( new UAVObjectField("BoardRotation", "deg", UAVObjectField.FieldType.INT16, BoardRotationElemNames, null) ); + + List ZeroDuringArmingElemNames = new ArrayList(); + ZeroDuringArmingElemNames.add("0"); + List ZeroDuringArmingEnumOptions = new ArrayList(); + ZeroDuringArmingEnumOptions.add("FALSE"); + ZeroDuringArmingEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ZeroDuringArming", "channel", UAVObjectField.FieldType.ENUM, ZeroDuringArmingElemNames, ZeroDuringArmingEnumOptions) ); + + List BiasCorrectGyroElemNames = new ArrayList(); + BiasCorrectGyroElemNames.add("0"); + List BiasCorrectGyroEnumOptions = new ArrayList(); + BiasCorrectGyroEnumOptions.add("FALSE"); + BiasCorrectGyroEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectGyro", "channel", UAVObjectField.FieldType.ENUM, BiasCorrectGyroElemNames, BiasCorrectGyroEnumOptions) ); + + List TrimFlightElemNames = new ArrayList(); + TrimFlightElemNames.add("0"); + List TrimFlightEnumOptions = new ArrayList(); + TrimFlightEnumOptions.add("NORMAL"); + TrimFlightEnumOptions.add("START"); + TrimFlightEnumOptions.add("LOAD"); + fields.add( new UAVObjectField("TrimFlight", "channel", UAVObjectField.FieldType.ENUM, TrimFlightElemNames, TrimFlightEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -114,12 +152,22 @@ public class AttitudeSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.05); + getField("AccelKi").setValue(0.0001); + getField("YawBiasRate").setValue(1e-06); getField("AccelBias").setValue(0,0); getField("AccelBias").setValue(0,1); getField("AccelBias").setValue(0,2); - getField("GyroGain").setValue(0.42); - getField("AccelKp").setValue(0.01); - getField("AccelKi").setValue(0.0001); + getField("GyroBias").setValue(0,0); + getField("GyroBias").setValue(0,1); + getField("GyroBias").setValue(0,2); + getField("BoardRotation").setValue(0,0); + getField("BoardRotation").setValue(0,1); + getField("BoardRotation").setValue(0,2); + getField("ZeroDuringArming").setValue("TRUE"); + getField("BiasCorrectGyro").setValue("TRUE"); + getField("TrimFlight").setValue("NORMAL"); } @@ -148,7 +196,7 @@ public class AttitudeSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x327BF29A; + protected static final int OBJID = 0xC307BC4A; protected static final String NAME = "AttitudeSettings"; protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index a2c2c7e3d..ecde53985 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -136,7 +136,7 @@ public class BaroAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0xED4424F6; + protected static final int OBJID = 0x99622E6A; protected static final String NAME = "BaroAltitude"; protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java new file mode 100644 index 000000000..7a36ec1ea --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired camera outputs. Comes from @ref CameraStabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired camera outputs. Comes from @ref CameraStabilization module. + +generated from cameradesired.xml + **/ +public class CameraDesired extends UAVDataObject { + + public CameraDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraDesired obj = new CameraDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraDesired)(objMngr.getObject(CameraDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x531F544E; + protected static final String NAME = "CameraDesired"; + protected static String DESCRIPTION = "Desired camera outputs. Comes from @ref CameraStabilization module."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java new file mode 100644 index 000000000..a8e03df32 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -0,0 +1,205 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref CameraStab mmodule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref CameraStab mmodule + +generated from camerastabsettings.xml + **/ +public class CameraStabSettings extends UAVDataObject { + + public CameraStabSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.FLOAT32, MaxAxisLockRateElemNames, null) ); + + List ResponseTimeElemNames = new ArrayList(); + ResponseTimeElemNames.add("Roll"); + ResponseTimeElemNames.add("Pitch"); + ResponseTimeElemNames.add("Yaw"); + fields.add( new UAVObjectField("ResponseTime", "ms", UAVObjectField.FieldType.UINT16, ResponseTimeElemNames, null) ); + + List InputElemNames = new ArrayList(); + InputElemNames.add("Roll"); + InputElemNames.add("Pitch"); + InputElemNames.add("Yaw"); + List InputEnumOptions = new ArrayList(); + InputEnumOptions.add("Accessory0"); + InputEnumOptions.add("Accessory1"); + InputEnumOptions.add("Accessory2"); + InputEnumOptions.add("Accessory3"); + InputEnumOptions.add("Accessory4"); + InputEnumOptions.add("Accessory5"); + InputEnumOptions.add("None"); + fields.add( new UAVObjectField("Input", "channel", UAVObjectField.FieldType.ENUM, InputElemNames, InputEnumOptions) ); + + List InputRangeElemNames = new ArrayList(); + InputRangeElemNames.add("Roll"); + InputRangeElemNames.add("Pitch"); + InputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRange", "deg", UAVObjectField.FieldType.UINT8, InputRangeElemNames, null) ); + + List InputRateElemNames = new ArrayList(); + InputRateElemNames.add("Roll"); + InputRateElemNames.add("Pitch"); + InputRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRate", "deg/s", UAVObjectField.FieldType.UINT8, InputRateElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + List OutputRangeElemNames = new ArrayList(); + OutputRangeElemNames.add("Roll"); + OutputRangeElemNames.add("Pitch"); + OutputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("OutputRange", "deg", UAVObjectField.FieldType.UINT8, OutputRangeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAxisLockRate").setValue(1); + getField("ResponseTime").setValue(150,0); + getField("ResponseTime").setValue(150,1); + getField("ResponseTime").setValue(150,2); + getField("Input").setValue("None",0); + getField("Input").setValue("None",1); + getField("Input").setValue("None",2); + getField("InputRange").setValue(20,0); + getField("InputRange").setValue(20,1); + getField("InputRange").setValue(20,2); + getField("InputRate").setValue(50,0); + getField("InputRate").setValue(50,1); + getField("InputRate").setValue(50,2); + getField("StabilizationMode").setValue("Attitude",0); + getField("StabilizationMode").setValue("Attitude",1); + getField("StabilizationMode").setValue("Attitude",2); + getField("OutputRange").setValue(20,0); + getField("OutputRange").setValue(20,1); + getField("OutputRange").setValue(20,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraStabSettings obj = new CameraStabSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraStabSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraStabSettings)(objMngr.getObject(CameraStabSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3B95DDBA; + protected static final String NAME = "CameraStabSettings"; + protected static String DESCRIPTION = "Settings for the @ref CameraStab mmodule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java similarity index 74% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index 675f9b592..b22b8185e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Select baud rate of telemetry. Warning - this must match your modem. + * Allows testers to simulate various fault scenarios. * * @see The GNU Public License (GPL) Version 3 * @@ -39,29 +39,28 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Select baud rate of telemetry. Warning - this must match your modem. +Allows testers to simulate various fault scenarios. -generated from telemetrysettings.xml +generated from faultsettings.xml **/ -public class TelemetrySettings extends UAVDataObject { +public class FaultSettings extends UAVDataObject { - public TelemetrySettings() { + public FaultSettings() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List SpeedElemNames = new ArrayList(); - SpeedElemNames.add("0"); - List SpeedEnumOptions = new ArrayList(); - SpeedEnumOptions.add("2400"); - SpeedEnumOptions.add("4800"); - SpeedEnumOptions.add("9600"); - SpeedEnumOptions.add("19200"); - SpeedEnumOptions.add("38400"); - SpeedEnumOptions.add("57600"); - SpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + List ActivateFaultElemNames = new ArrayList(); + ActivateFaultElemNames.add("0"); + List ActivateFaultEnumOptions = new ArrayList(); + ActivateFaultEnumOptions.add("NoFault"); + ActivateFaultEnumOptions.add("ModuleInitAssert"); + ActivateFaultEnumOptions.add("InitOutOfMemory"); + ActivateFaultEnumOptions.add("InitBusError"); + ActivateFaultEnumOptions.add("RunawayTask"); + ActivateFaultEnumOptions.add("TaskOutOfMemory"); + fields.add( new UAVObjectField("ActivateFault", "fault", UAVObjectField.FieldType.ENUM, ActivateFaultElemNames, ActivateFaultEnumOptions) ); // Compute the number of bytes for this object @@ -108,7 +107,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue("57600"); + getField("ActivateFault").setValue("NoFault"); } @@ -120,7 +119,7 @@ public class TelemetrySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - TelemetrySettings obj = new TelemetrySettings(); + FaultSettings obj = new FaultSettings(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -131,15 +130,15 @@ public class TelemetrySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + public FaultSettings GetInstance(UAVObjectManager objMngr, int instID) { - return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + return (FaultSettings)(objMngr.getObject(FaultSettings.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA608C526; - protected static final String NAME = "TelemetrySettings"; - protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final int OBJID = 0x2778BA3C; + protected static final String NAME = "FaultSettings"; + protected static String DESCRIPTION = "Allows testers to simulate various fault scenarios."; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 1 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 493d6cd64..71c681bd2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Firmware IAP + * Queries board for SN, model, revision, and sends reset command * * @see The GNU Public License (GPL) Version 3 * @@ -39,7 +39,7 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Firmware IAP +Queries board for SN, model, revision, and sends reset command generated from firmwareiapobj.xml **/ @@ -51,10 +51,18 @@ public class FirmwareIAPObj extends UAVDataObject { List fields = new ArrayList(); + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + List CommandElemNames = new ArrayList(); CommandElemNames.add("0"); fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List DescriptionElemNames = new ArrayList(); DescriptionElemNames.add("0"); DescriptionElemNames.add("1"); @@ -96,71 +104,22 @@ public class FirmwareIAPObj extends UAVDataObject { DescriptionElemNames.add("37"); DescriptionElemNames.add("38"); DescriptionElemNames.add("39"); - DescriptionElemNames.add("40"); - DescriptionElemNames.add("41"); - DescriptionElemNames.add("42"); - DescriptionElemNames.add("43"); - DescriptionElemNames.add("44"); - DescriptionElemNames.add("45"); - DescriptionElemNames.add("46"); - DescriptionElemNames.add("47"); - DescriptionElemNames.add("48"); - DescriptionElemNames.add("49"); - DescriptionElemNames.add("50"); - DescriptionElemNames.add("51"); - DescriptionElemNames.add("52"); - DescriptionElemNames.add("53"); - DescriptionElemNames.add("54"); - DescriptionElemNames.add("55"); - DescriptionElemNames.add("56"); - DescriptionElemNames.add("57"); - DescriptionElemNames.add("58"); - DescriptionElemNames.add("59"); - DescriptionElemNames.add("60"); - DescriptionElemNames.add("61"); - DescriptionElemNames.add("62"); - DescriptionElemNames.add("63"); - DescriptionElemNames.add("64"); - DescriptionElemNames.add("65"); - DescriptionElemNames.add("66"); - DescriptionElemNames.add("67"); - DescriptionElemNames.add("68"); - DescriptionElemNames.add("69"); - DescriptionElemNames.add("70"); - DescriptionElemNames.add("71"); - DescriptionElemNames.add("72"); - DescriptionElemNames.add("73"); - DescriptionElemNames.add("74"); - DescriptionElemNames.add("75"); - DescriptionElemNames.add("76"); - DescriptionElemNames.add("77"); - DescriptionElemNames.add("78"); - DescriptionElemNames.add("79"); - DescriptionElemNames.add("80"); - DescriptionElemNames.add("81"); - DescriptionElemNames.add("82"); - DescriptionElemNames.add("83"); - DescriptionElemNames.add("84"); - DescriptionElemNames.add("85"); - DescriptionElemNames.add("86"); - DescriptionElemNames.add("87"); - DescriptionElemNames.add("88"); - DescriptionElemNames.add("89"); - DescriptionElemNames.add("90"); - DescriptionElemNames.add("91"); - DescriptionElemNames.add("92"); - DescriptionElemNames.add("93"); - DescriptionElemNames.add("94"); - DescriptionElemNames.add("95"); - DescriptionElemNames.add("96"); - DescriptionElemNames.add("97"); - DescriptionElemNames.add("98"); - DescriptionElemNames.add("99"); fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); - List BoardRevisionElemNames = new ArrayList(); - BoardRevisionElemNames.add("0"); - fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); List BoardTypeElemNames = new ArrayList(); BoardTypeElemNames.add("0"); @@ -170,10 +129,6 @@ public class FirmwareIAPObj extends UAVDataObject { ArmResetElemNames.add("0"); fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); - List crcElemNames = new ArrayList(); - crcElemNames.add("0"); - fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -247,9 +202,9 @@ public class FirmwareIAPObj extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1A8ECC2; + protected static final int OBJID = 0x3CCDFB68; protected static final String NAME = "FirmwareIAPObj"; - protected static String DESCRIPTION = "Firmware IAP"; + protected static String DESCRIPTION = "Queries board for SN, model, revision, and sends reset command"; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java new file mode 100644 index 000000000..a3bc23eb3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -0,0 +1,177 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Flight Battery configuration. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Flight Battery configuration. + +generated from flightbatterysettings.xml + **/ +public class FlightBatterySettings extends UAVDataObject { + + public FlightBatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CapacityElemNames = new ArrayList(); + CapacityElemNames.add("0"); + fields.add( new UAVObjectField("Capacity", "mAh", UAVObjectField.FieldType.UINT32, CapacityElemNames, null) ); + + List VoltageThresholdsElemNames = new ArrayList(); + VoltageThresholdsElemNames.add("Warning"); + VoltageThresholdsElemNames.add("Alarm"); + fields.add( new UAVObjectField("VoltageThresholds", "V", UAVObjectField.FieldType.FLOAT32, VoltageThresholdsElemNames, null) ); + + List SensorCalibrationsElemNames = new ArrayList(); + SensorCalibrationsElemNames.add("VoltageFactor"); + SensorCalibrationsElemNames.add("CurrentFactor"); + fields.add( new UAVObjectField("SensorCalibrations", "", UAVObjectField.FieldType.FLOAT32, SensorCalibrationsElemNames, null) ); + + List TypeElemNames = new ArrayList(); + TypeElemNames.add("0"); + List TypeEnumOptions = new ArrayList(); + TypeEnumOptions.add("LiPo"); + TypeEnumOptions.add("A123"); + TypeEnumOptions.add("LiCo"); + TypeEnumOptions.add("LiFeSO4"); + TypeEnumOptions.add("None"); + fields.add( new UAVObjectField("Type", "", UAVObjectField.FieldType.ENUM, TypeElemNames, TypeEnumOptions) ); + + List NbCellsElemNames = new ArrayList(); + NbCellsElemNames.add("0"); + fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); + + List SensorTypeElemNames = new ArrayList(); + SensorTypeElemNames.add("0"); + List SensorTypeEnumOptions = new ArrayList(); + SensorTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Capacity").setValue(2200); + getField("VoltageThresholds").setValue(9.8,0); + getField("VoltageThresholds").setValue(9.2,1); + getField("SensorCalibrations").setValue(1,0); + getField("SensorCalibrations").setValue(1,1); + getField("Type").setValue("LiPo"); + getField("NbCells").setValue(3); + getField("SensorType").setValue("None"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatterySettings obj = new FlightBatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatterySettings)(objMngr.getObject(FlightBatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF172BB18; + protected static final String NAME = "FlightBatterySettings"; + protected static String DESCRIPTION = "Flight Battery configuration."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index d9fba1de5..82fcfae47 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -154,7 +154,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x791A50E; + protected static final int OBJID = 0x8C0D756; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index fdc5bfcb0..dbe959f96 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -133,7 +133,7 @@ public class FlightPlanControl extends UAVDataObject { } // Constants - protected static final int OBJID = 0x6B4FE6DA; + protected static final int OBJID = 0x53E3F180; protected static final String NAME = "FlightPlanControl"; protected static String DESCRIPTION = "Control the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 383e4aff0..6fc39a26e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -129,7 +129,7 @@ public class FlightPlanSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x85368422; + protected static final int OBJID = 0x92E9FF76; protected static final String NAME = "FlightPlanSettings"; protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 2303514c0..7b78bce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -51,6 +51,19 @@ public class FlightPlanStatus extends UAVDataObject { List fields = new ArrayList(); + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List DebugElemNames = new ArrayList(); + DebugElemNames.add("0"); + DebugElemNames.add("1"); + fields.add( new UAVObjectField("Debug", "", UAVObjectField.FieldType.FLOAT32, DebugElemNames, null) ); + List StatusElemNames = new ArrayList(); StatusElemNames.add("0"); List StatusEnumOptions = new ArrayList(); @@ -83,22 +96,6 @@ public class FlightPlanStatus extends UAVDataObject { ErrorTypeEnumOptions.add("UnknownError"); fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); - List ErrorFileIDElemNames = new ArrayList(); - ErrorFileIDElemNames.add("0"); - fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); - - List ErrorLineNumElemNames = new ArrayList(); - ErrorLineNumElemNames.add("0"); - fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); - - List Debug1ElemNames = new ArrayList(); - Debug1ElemNames.add("0"); - fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); - - List Debug2ElemNames = new ArrayList(); - Debug2ElemNames.add("0"); - fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -144,10 +141,10 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Debug").setValue(0,0); + getField("Debug").setValue(0,1); getField("Status").setValue("Stopped"); getField("ErrorType").setValue("None"); - getField("Debug1").setValue(0); - getField("Debug2").setValue(0); } @@ -176,7 +173,7 @@ public class FlightPlanStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9FC14812; + protected static final int OBJID = 0x2206EE46; protected static final String NAME = "FlightPlanStatus"; protected static String DESCRIPTION = "Status of the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java new file mode 100644 index 000000000..d775b21e7 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -0,0 +1,155 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains major flight status information for other modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains major flight status information for other modules. + +generated from flightstatus.xml + **/ +public class FlightStatus extends UAVDataObject { + + public FlightStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("Disarmed"); + ArmedEnumOptions.add("Arming"); + ArmedEnumOptions.add("Armed"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Armed").setValue("Disarmed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightStatus obj = new FlightStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightStatus)(objMngr.getObject(FlightStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x743DB13C; + protected static final String NAME = "FlightStatus"; + protected static String DESCRIPTION = "Contains major flight status information for other modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index b58fe6d46..403ea1d5e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -51,15 +51,6 @@ public class FlightTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class FlightTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class FlightTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x660C265E; + protected static final int OBJID = 0x2F7E2902; protected static final String NAME = "FlightTelemetryStats"; protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java new file mode 100644 index 000000000..3cb3811ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A receiver channel group carried over the telemetry link. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A receiver channel group carried over the telemetry link. + +generated from gcsreceiver.xml + **/ +public class GCSReceiver extends UAVDataObject { + + public GCSReceiver() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSReceiver obj = new GCSReceiver(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSReceiver GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSReceiver)(objMngr.getObject(GCSReceiver.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xCC7E2BBC; + protected static final String NAME = "GCSReceiver"; + protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index 0f304d45d..b32f551ce 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -51,15 +51,6 @@ public class GCSTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class GCSTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class GCSTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x771E1046; + protected static final int OBJID = 0xABC72744; protected static final String NAME = "GCSTelemetryStats"; protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 889091e0e..5f4e20b46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -51,15 +51,6 @@ public class GPSPosition extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("NoGPS"); - StatusEnumOptions.add("NoFix"); - StatusEnumOptions.add("Fix2D"); - StatusEnumOptions.add("Fix3D"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -84,10 +75,6 @@ public class GPSPosition extends UAVDataObject { GroundspeedElemNames.add("0"); fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); - List SatellitesElemNames = new ArrayList(); - SatellitesElemNames.add("0"); - fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); - List PDOPElemNames = new ArrayList(); PDOPElemNames.add("0"); fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); @@ -100,6 +87,19 @@ public class GPSPosition extends UAVDataObject { VDOPElemNames.add("0"); fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -173,7 +173,7 @@ public class GPSPosition extends UAVDataObject { } // Constants - protected static final int OBJID = 0xB5495042; + protected static final int OBJID = 0xE2A323B6; protected static final String NAME = "GPSPosition"; protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index fa1100207..bb331132d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -51,29 +51,6 @@ public class GPSSatellites extends UAVDataObject { List fields = new ArrayList(); - List SatsInViewElemNames = new ArrayList(); - SatsInViewElemNames.add("0"); - fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); - - List PRNElemNames = new ArrayList(); - PRNElemNames.add("0"); - PRNElemNames.add("1"); - PRNElemNames.add("2"); - PRNElemNames.add("3"); - PRNElemNames.add("4"); - PRNElemNames.add("5"); - PRNElemNames.add("6"); - PRNElemNames.add("7"); - PRNElemNames.add("8"); - PRNElemNames.add("9"); - PRNElemNames.add("10"); - PRNElemNames.add("11"); - PRNElemNames.add("12"); - PRNElemNames.add("13"); - PRNElemNames.add("14"); - PRNElemNames.add("15"); - fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); - List ElevationElemNames = new ArrayList(); ElevationElemNames.add("0"); ElevationElemNames.add("1"); @@ -112,6 +89,29 @@ public class GPSSatellites extends UAVDataObject { AzimuthElemNames.add("15"); fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + List SNRElemNames = new ArrayList(); SNRElemNames.add("0"); SNRElemNames.add("1"); @@ -204,7 +204,7 @@ public class GPSSatellites extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD62FA3AE; + protected static final int OBJID = 0x920D998; protected static final String NAME = "GPSSatellites"; protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5ff55cc2e..5aa4df7bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -51,6 +51,10 @@ public class GPSTime extends UAVDataObject { List fields = new ArrayList(); + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + List MonthElemNames = new ArrayList(); MonthElemNames.add("0"); fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); @@ -59,10 +63,6 @@ public class GPSTime extends UAVDataObject { DayElemNames.add("0"); fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); - List YearElemNames = new ArrayList(); - YearElemNames.add("0"); - fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); - List HourElemNames = new ArrayList(); HourElemNames.add("0"); fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); @@ -148,7 +148,7 @@ public class GPSTime extends UAVDataObject { } // Constants - protected static final int OBJID = 0x56FFF0A2; + protected static final int OBJID = 0xD4478084; protected static final String NAME = "GPSTime"; protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2fe8bb437..205384efe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -51,29 +51,24 @@ public class GuidanceSettings extends UAVDataObject { List fields = new ArrayList(); - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List HorizontalPElemNames = new ArrayList(); - HorizontalPElemNames.add("Kp"); - HorizontalPElemNames.add("Max"); - fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - List VerticalPElemNames = new ArrayList(); - VerticalPElemNames.add("Kp"); - VerticalPElemNames.add("Max"); - fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); List VerticalVelPIDElemNames = new ArrayList(); VerticalVelPIDElemNames.add("Kp"); @@ -82,13 +77,6 @@ public class GuidanceSettings extends UAVDataObject { VerticalVelPIDElemNames.add("ILimit"); fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - List MaxRollPitchElemNames = new ArrayList(); MaxRollPitchElemNames.add("0"); fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); @@ -97,6 +85,28 @@ public class GuidanceSettings extends UAVDataObject { UpdatePeriodElemNames.add("0"); fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -142,22 +152,26 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("HorizontalP").setValue(0.2,0); - getField("HorizontalP").setValue(150,1); - getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.001,1); + getField("HorizontalPosPI").setValue(300,2); + getField("HorizontalVelPID").setValue(0.05,0); getField("HorizontalVelPID").setValue(0.002,1); getField("HorizontalVelPID").setValue(0,2); getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalP").setValue(0.1,0); - getField("VerticalP").setValue(200,1); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); getField("VerticalVelPID").setValue(0.1,0); getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(300); + getField("VerticalVelMax").setValue(150); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); } @@ -186,7 +200,7 @@ public class GuidanceSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x74740AA2; + protected static final int OBJID = 0x6EA79FB4; protected static final String NAME = "GuidanceSettings"; protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 5941c069c..68abb3633 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -51,13 +51,6 @@ public class HomeLocation extends UAVDataObject { List fields = new ArrayList(); - List SetElemNames = new ArrayList(); - SetElemNames.add("0"); - List SetEnumOptions = new ArrayList(); - SetEnumOptions.add("FALSE"); - SetEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -94,6 +87,17 @@ public class HomeLocation extends UAVDataObject { BeElemNames.add("2"); fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + List g_eElemNames = new ArrayList(); + g_eElemNames.add("0"); + fields.add( new UAVObjectField("g_e", "m/s^2", UAVObjectField.FieldType.FLOAT32, g_eElemNames, null) ); + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -139,7 +143,6 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); @@ -158,6 +161,8 @@ public class HomeLocation extends UAVDataObject { getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); + getField("g_e").setValue(9.81); + getField("Set").setValue("FALSE"); } @@ -186,7 +191,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD6008ED2; + protected static final int OBJID = 0x5BB3AEFC; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java new file mode 100644 index 000000000..83b7ae7b6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -0,0 +1,291 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Selection of optional hardware configurations. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Selection of optional hardware configurations. + +generated from hwsettings.xml + **/ +public class HwSettings extends UAVDataObject { + + public HwSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CC_RcvrPortElemNames = new ArrayList(); + CC_RcvrPortElemNames.add("0"); + List CC_RcvrPortEnumOptions = new ArrayList(); + CC_RcvrPortEnumOptions.add("Disabled"); + CC_RcvrPortEnumOptions.add("PWM"); + CC_RcvrPortEnumOptions.add("PPM"); + CC_RcvrPortEnumOptions.add("PPM+Outputs"); + CC_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("CC_RcvrPort", "function", UAVObjectField.FieldType.ENUM, CC_RcvrPortElemNames, CC_RcvrPortEnumOptions) ); + + List CC_MainPortElemNames = new ArrayList(); + CC_MainPortElemNames.add("0"); + List CC_MainPortEnumOptions = new ArrayList(); + CC_MainPortEnumOptions.add("Disabled"); + CC_MainPortEnumOptions.add("Telemetry"); + CC_MainPortEnumOptions.add("GPS"); + CC_MainPortEnumOptions.add("S.Bus"); + CC_MainPortEnumOptions.add("DSM2"); + CC_MainPortEnumOptions.add("DSMX (10bit)"); + CC_MainPortEnumOptions.add("DSMX (11bit)"); + CC_MainPortEnumOptions.add("ComAux"); + CC_MainPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_MainPort", "function", UAVObjectField.FieldType.ENUM, CC_MainPortElemNames, CC_MainPortEnumOptions) ); + + List CC_FlexiPortElemNames = new ArrayList(); + CC_FlexiPortElemNames.add("0"); + List CC_FlexiPortEnumOptions = new ArrayList(); + CC_FlexiPortEnumOptions.add("Disabled"); + CC_FlexiPortEnumOptions.add("Telemetry"); + CC_FlexiPortEnumOptions.add("GPS"); + CC_FlexiPortEnumOptions.add("I2C"); + CC_FlexiPortEnumOptions.add("DSM2"); + CC_FlexiPortEnumOptions.add("DSMX (10bit)"); + CC_FlexiPortEnumOptions.add("DSMX (11bit)"); + CC_FlexiPortEnumOptions.add("ComAux"); + CC_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); + + List OP_RcvrPortElemNames = new ArrayList(); + OP_RcvrPortElemNames.add("0"); + List OP_RcvrPortEnumOptions = new ArrayList(); + OP_RcvrPortEnumOptions.add("Disabled"); + OP_RcvrPortEnumOptions.add("PWM"); + OP_RcvrPortEnumOptions.add("PPM"); + OP_RcvrPortEnumOptions.add("DSM2"); + OP_RcvrPortEnumOptions.add("DSMX (10bit)"); + OP_RcvrPortEnumOptions.add("DSMX (11bit)"); + OP_RcvrPortEnumOptions.add("Debug"); + fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + + List OP_MainPortElemNames = new ArrayList(); + OP_MainPortElemNames.add("0"); + List OP_MainPortEnumOptions = new ArrayList(); + OP_MainPortEnumOptions.add("Disabled"); + OP_MainPortEnumOptions.add("Telemetry"); + fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + + List OP_FlexiPortElemNames = new ArrayList(); + OP_FlexiPortElemNames.add("0"); + List OP_FlexiPortEnumOptions = new ArrayList(); + OP_FlexiPortEnumOptions.add("Disabled"); + OP_FlexiPortEnumOptions.add("GPS"); + fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List GPSSpeedElemNames = new ArrayList(); + GPSSpeedElemNames.add("0"); + List GPSSpeedEnumOptions = new ArrayList(); + GPSSpeedEnumOptions.add("2400"); + GPSSpeedEnumOptions.add("4800"); + GPSSpeedEnumOptions.add("9600"); + GPSSpeedEnumOptions.add("19200"); + GPSSpeedEnumOptions.add("38400"); + GPSSpeedEnumOptions.add("57600"); + GPSSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("GPSSpeed", "bps", UAVObjectField.FieldType.ENUM, GPSSpeedElemNames, GPSSpeedEnumOptions) ); + + List ComUsbBridgeSpeedElemNames = new ArrayList(); + ComUsbBridgeSpeedElemNames.add("0"); + List ComUsbBridgeSpeedEnumOptions = new ArrayList(); + ComUsbBridgeSpeedEnumOptions.add("2400"); + ComUsbBridgeSpeedEnumOptions.add("4800"); + ComUsbBridgeSpeedEnumOptions.add("9600"); + ComUsbBridgeSpeedEnumOptions.add("19200"); + ComUsbBridgeSpeedEnumOptions.add("38400"); + ComUsbBridgeSpeedEnumOptions.add("57600"); + ComUsbBridgeSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); + + List USB_DeviceTypeElemNames = new ArrayList(); + USB_DeviceTypeElemNames.add("0"); + List USB_DeviceTypeEnumOptions = new ArrayList(); + USB_DeviceTypeEnumOptions.add("HID-only"); + USB_DeviceTypeEnumOptions.add("HID+VCP"); + USB_DeviceTypeEnumOptions.add("VCP-only"); + fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); + + List USB_HIDPortElemNames = new ArrayList(); + USB_HIDPortElemNames.add("0"); + List USB_HIDPortEnumOptions = new ArrayList(); + USB_HIDPortEnumOptions.add("USBTelemetry"); + USB_HIDPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_HIDPort", "function", UAVObjectField.FieldType.ENUM, USB_HIDPortElemNames, USB_HIDPortEnumOptions) ); + + List USB_VCPPortElemNames = new ArrayList(); + USB_VCPPortElemNames.add("0"); + List USB_VCPPortEnumOptions = new ArrayList(); + USB_VCPPortEnumOptions.add("USBTelemetry"); + USB_VCPPortEnumOptions.add("ComBridge"); + USB_VCPPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_VCPPort", "function", UAVObjectField.FieldType.ENUM, USB_VCPPortElemNames, USB_VCPPortEnumOptions) ); + + List OptionalModulesElemNames = new ArrayList(); + OptionalModulesElemNames.add("CameraStab"); + OptionalModulesElemNames.add("GPS"); + OptionalModulesElemNames.add("ComUsbBridge"); + OptionalModulesElemNames.add("Fault"); + OptionalModulesElemNames.add("Altitude"); + List OptionalModulesEnumOptions = new ArrayList(); + OptionalModulesEnumOptions.add("Disabled"); + OptionalModulesEnumOptions.add("Enabled"); + fields.add( new UAVObjectField("OptionalModules", "", UAVObjectField.FieldType.ENUM, OptionalModulesElemNames, OptionalModulesEnumOptions) ); + + List DSMxBindElemNames = new ArrayList(); + DSMxBindElemNames.add("0"); + fields.add( new UAVObjectField("DSMxBind", "", UAVObjectField.FieldType.UINT8, DSMxBindElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("CC_RcvrPort").setValue("PWM"); + getField("CC_MainPort").setValue("Disabled"); + getField("CC_FlexiPort").setValue("Disabled"); + getField("OP_RcvrPort").setValue("PWM"); + getField("OP_MainPort").setValue("Telemetry"); + getField("OP_FlexiPort").setValue("GPS"); + getField("TelemetrySpeed").setValue("57600"); + getField("GPSSpeed").setValue("57600"); + getField("ComUsbBridgeSpeed").setValue("57600"); + getField("USB_DeviceType").setValue("HID-only"); + getField("USB_HIDPort").setValue("USBTelemetry"); + getField("USB_VCPPort").setValue("Disabled"); + getField("OptionalModules").setValue("Disabled",0); + getField("OptionalModules").setValue("Disabled",1); + getField("OptionalModules").setValue("Disabled",2); + getField("OptionalModules").setValue("Disabled",3); + getField("OptionalModules").setValue("Disabled",4); + getField("DSMxBind").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HwSettings obj = new HwSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HwSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (HwSettings)(objMngr.getObject(HwSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2EE6575A; + protected static final String NAME = "HwSettings"; + protected static String DESCRIPTION = "Selection of optional hardware configurations."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index fc68e2902..abd8f41f6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -51,6 +51,22 @@ public class I2CStats extends UAVDataObject { List fields = new ArrayList(); + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + List event_errorsElemNames = new ArrayList(); event_errorsElemNames.add("0"); fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); @@ -79,22 +95,6 @@ public class I2CStats extends UAVDataObject { last_error_typeEnumOptions.add("INTERRUPT"); fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); - List evirq_logElemNames = new ArrayList(); - evirq_logElemNames.add("0"); - evirq_logElemNames.add("1"); - evirq_logElemNames.add("2"); - evirq_logElemNames.add("3"); - evirq_logElemNames.add("4"); - fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); - - List erirq_logElemNames = new ArrayList(); - erirq_logElemNames.add("0"); - erirq_logElemNames.add("1"); - erirq_logElemNames.add("2"); - erirq_logElemNames.add("3"); - erirq_logElemNames.add("4"); - fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); - List event_logElemNames = new ArrayList(); event_logElemNames.add("0"); event_logElemNames.add("1"); @@ -227,7 +227,7 @@ public class I2CStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x23CE9E9C; + protected static final int OBJID = 0xB714823E; protected static final String NAME = "I2CStats"; protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 636f30946..6ac5a1b2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -51,19 +51,9 @@ public class ManualControlCommand extends UAVDataObject { List fields = new ArrayList(); - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - List ArmedElemNames = new ArrayList(); - ArmedElemNames.add("0"); - List ArmedEnumOptions = new ArrayList(); - ArmedEnumOptions.add("False"); - ArmedEnumOptions.add("True"); - fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); List RollElemNames = new ArrayList(); RollElemNames.add("0"); @@ -77,32 +67,9 @@ public class ManualControlCommand extends UAVDataObject { YawElemNames.add("0"); fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Manual"); - FlightModeEnumOptions.add("Stabilized1"); - FlightModeEnumOptions.add("Stabilized2"); - FlightModeEnumOptions.add("Stabilized3"); - FlightModeEnumOptions.add("VelocityControl"); - FlightModeEnumOptions.add("PositionHold"); - fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + List CollectiveElemNames = new ArrayList(); + CollectiveElemNames.add("0"); + fields.add( new UAVObjectField("Collective", "%", UAVObjectField.FieldType.FLOAT32, CollectiveElemNames, null) ); List ChannelElemNames = new ArrayList(); ChannelElemNames.add("0"); @@ -113,8 +80,16 @@ public class ManualControlCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -188,7 +163,7 @@ public class ManualControlCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0x926794; + protected static final int OBJID = 0x1E82C2D2; protected static final String NAME = "ManualControlCommand"; protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index 83697999a..bb846695d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,125 +51,77 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); - List InputModeElemNames = new ArrayList(); - InputModeElemNames.add("0"); - List InputModeEnumOptions = new ArrayList(); - InputModeEnumOptions.add("PWM"); - InputModeEnumOptions.add("PPM"); - InputModeEnumOptions.add("Spektrum"); - fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("Throttle"); + ChannelMinElemNames.add("Roll"); + ChannelMinElemNames.add("Pitch"); + ChannelMinElemNames.add("Yaw"); + ChannelMinElemNames.add("FlightMode"); + ChannelMinElemNames.add("Collective"); + ChannelMinElemNames.add("Accessory0"); + ChannelMinElemNames.add("Accessory1"); + ChannelMinElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - List RollEnumOptions = new ArrayList(); - RollEnumOptions.add("Channel1"); - RollEnumOptions.add("Channel2"); - RollEnumOptions.add("Channel3"); - RollEnumOptions.add("Channel4"); - RollEnumOptions.add("Channel5"); - RollEnumOptions.add("Channel6"); - RollEnumOptions.add("Channel7"); - RollEnumOptions.add("Channel8"); - RollEnumOptions.add("None"); - fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("Throttle"); + ChannelNeutralElemNames.add("Roll"); + ChannelNeutralElemNames.add("Pitch"); + ChannelNeutralElemNames.add("Yaw"); + ChannelNeutralElemNames.add("FlightMode"); + ChannelNeutralElemNames.add("Collective"); + ChannelNeutralElemNames.add("Accessory0"); + ChannelNeutralElemNames.add("Accessory1"); + ChannelNeutralElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - List PitchEnumOptions = new ArrayList(); - PitchEnumOptions.add("Channel1"); - PitchEnumOptions.add("Channel2"); - PitchEnumOptions.add("Channel3"); - PitchEnumOptions.add("Channel4"); - PitchEnumOptions.add("Channel5"); - PitchEnumOptions.add("Channel6"); - PitchEnumOptions.add("Channel7"); - PitchEnumOptions.add("Channel8"); - PitchEnumOptions.add("None"); - fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("Throttle"); + ChannelMaxElemNames.add("Roll"); + ChannelMaxElemNames.add("Pitch"); + ChannelMaxElemNames.add("Yaw"); + ChannelMaxElemNames.add("FlightMode"); + ChannelMaxElemNames.add("Collective"); + ChannelMaxElemNames.add("Accessory0"); + ChannelMaxElemNames.add("Accessory1"); + ChannelMaxElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - List YawEnumOptions = new ArrayList(); - YawEnumOptions.add("Channel1"); - YawEnumOptions.add("Channel2"); - YawEnumOptions.add("Channel3"); - YawEnumOptions.add("Channel4"); - YawEnumOptions.add("Channel5"); - YawEnumOptions.add("Channel6"); - YawEnumOptions.add("Channel7"); - YawEnumOptions.add("Channel8"); - YawEnumOptions.add("None"); - fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - List ThrottleEnumOptions = new ArrayList(); - ThrottleEnumOptions.add("Channel1"); - ThrottleEnumOptions.add("Channel2"); - ThrottleEnumOptions.add("Channel3"); - ThrottleEnumOptions.add("Channel4"); - ThrottleEnumOptions.add("Channel5"); - ThrottleEnumOptions.add("Channel6"); - ThrottleEnumOptions.add("Channel7"); - ThrottleEnumOptions.add("Channel8"); - ThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + List ChannelGroupsElemNames = new ArrayList(); + ChannelGroupsElemNames.add("Throttle"); + ChannelGroupsElemNames.add("Roll"); + ChannelGroupsElemNames.add("Pitch"); + ChannelGroupsElemNames.add("Yaw"); + ChannelGroupsElemNames.add("FlightMode"); + ChannelGroupsElemNames.add("Collective"); + ChannelGroupsElemNames.add("Accessory0"); + ChannelGroupsElemNames.add("Accessory1"); + ChannelGroupsElemNames.add("Accessory2"); + List ChannelGroupsEnumOptions = new ArrayList(); + ChannelGroupsEnumOptions.add("PWM"); + ChannelGroupsEnumOptions.add("PPM"); + ChannelGroupsEnumOptions.add("DSM (MainPort)"); + ChannelGroupsEnumOptions.add("DSM (FlexiPort)"); + ChannelGroupsEnumOptions.add("S.Bus"); + ChannelGroupsEnumOptions.add("GCS"); + ChannelGroupsEnumOptions.add("None"); + fields.add( new UAVObjectField("ChannelGroups", "Channel Group", UAVObjectField.FieldType.ENUM, ChannelGroupsElemNames, ChannelGroupsEnumOptions) ); - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Channel1"); - FlightModeEnumOptions.add("Channel2"); - FlightModeEnumOptions.add("Channel3"); - FlightModeEnumOptions.add("Channel4"); - FlightModeEnumOptions.add("Channel5"); - FlightModeEnumOptions.add("Channel6"); - FlightModeEnumOptions.add("Channel7"); - FlightModeEnumOptions.add("Channel8"); - FlightModeEnumOptions.add("None"); - fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - List Accessory1EnumOptions = new ArrayList(); - Accessory1EnumOptions.add("Channel1"); - Accessory1EnumOptions.add("Channel2"); - Accessory1EnumOptions.add("Channel3"); - Accessory1EnumOptions.add("Channel4"); - Accessory1EnumOptions.add("Channel5"); - Accessory1EnumOptions.add("Channel6"); - Accessory1EnumOptions.add("Channel7"); - Accessory1EnumOptions.add("Channel8"); - Accessory1EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - List Accessory2EnumOptions = new ArrayList(); - Accessory2EnumOptions.add("Channel1"); - Accessory2EnumOptions.add("Channel2"); - Accessory2EnumOptions.add("Channel3"); - Accessory2EnumOptions.add("Channel4"); - Accessory2EnumOptions.add("Channel5"); - Accessory2EnumOptions.add("Channel6"); - Accessory2EnumOptions.add("Channel7"); - Accessory2EnumOptions.add("Channel8"); - Accessory2EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - List Accessory3EnumOptions = new ArrayList(); - Accessory3EnumOptions.add("Channel1"); - Accessory3EnumOptions.add("Channel2"); - Accessory3EnumOptions.add("Channel3"); - Accessory3EnumOptions.add("Channel4"); - Accessory3EnumOptions.add("Channel5"); - Accessory3EnumOptions.add("Channel6"); - Accessory3EnumOptions.add("Channel7"); - Accessory3EnumOptions.add("Channel8"); - Accessory3EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + List ChannelNumberElemNames = new ArrayList(); + ChannelNumberElemNames.add("Throttle"); + ChannelNumberElemNames.add("Roll"); + ChannelNumberElemNames.add("Pitch"); + ChannelNumberElemNames.add("Yaw"); + ChannelNumberElemNames.add("FlightMode"); + ChannelNumberElemNames.add("Collective"); + ChannelNumberElemNames.add("Accessory0"); + ChannelNumberElemNames.add("Accessory1"); + ChannelNumberElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNumber", "channel", UAVObjectField.FieldType.UINT8, ChannelNumberElemNames, null) ); List ArmingElemNames = new ArrayList(); ArmingElemNames.add("0"); @@ -192,6 +144,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("None"); Stabilization1SettingsEnumOptions.add("Rate"); Stabilization1SettingsEnumOptions.add("Attitude"); + Stabilization1SettingsEnumOptions.add("AxisLock"); + Stabilization1SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -202,6 +156,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("None"); Stabilization2SettingsEnumOptions.add("Rate"); Stabilization2SettingsEnumOptions.add("Attitude"); + Stabilization2SettingsEnumOptions.add("AxisLock"); + Stabilization2SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -212,6 +168,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("None"); Stabilization3SettingsEnumOptions.add("Rate"); Stabilization3SettingsEnumOptions.add("Attitude"); + Stabilization3SettingsEnumOptions.add("AxisLock"); + Stabilization3SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -227,43 +185,6 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("PositionHold"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); - List ChannelMaxElemNames = new ArrayList(); - ChannelMaxElemNames.add("0"); - ChannelMaxElemNames.add("1"); - ChannelMaxElemNames.add("2"); - ChannelMaxElemNames.add("3"); - ChannelMaxElemNames.add("4"); - ChannelMaxElemNames.add("5"); - ChannelMaxElemNames.add("6"); - ChannelMaxElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - - List ChannelNeutralElemNames = new ArrayList(); - ChannelNeutralElemNames.add("0"); - ChannelNeutralElemNames.add("1"); - ChannelNeutralElemNames.add("2"); - ChannelNeutralElemNames.add("3"); - ChannelNeutralElemNames.add("4"); - ChannelNeutralElemNames.add("5"); - ChannelNeutralElemNames.add("6"); - ChannelNeutralElemNames.add("7"); - fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - - List ChannelMinElemNames = new ArrayList(); - ChannelMinElemNames.add("0"); - ChannelMinElemNames.add("1"); - ChannelMinElemNames.add("2"); - ChannelMinElemNames.add("3"); - ChannelMinElemNames.add("4"); - ChannelMinElemNames.add("5"); - ChannelMinElemNames.add("6"); - ChannelMinElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - - List ArmedTimeoutElemNames = new ArrayList(); - ArmedTimeoutElemNames.add("0"); - fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -309,44 +230,6 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue("PWM"); - getField("Roll").setValue("Channel1"); - getField("Pitch").setValue("Channel2"); - getField("Yaw").setValue("Channel3"); - getField("Throttle").setValue("Channel4"); - getField("FlightMode").setValue("Channel5"); - getField("Accessory1").setValue("None"); - getField("Accessory2").setValue("None"); - getField("Accessory3").setValue("None"); - getField("Arming").setValue("Always Disarmed"); - getField("Stabilization1Settings").setValue("Attitude",0); - getField("Stabilization1Settings").setValue("Attitude",1); - getField("Stabilization1Settings").setValue("Attitude",2); - getField("Stabilization2Settings").setValue("Attitude",0); - getField("Stabilization2Settings").setValue("Attitude",1); - getField("Stabilization2Settings").setValue("Attitude",2); - getField("Stabilization3Settings").setValue("Attitude",0); - getField("Stabilization3Settings").setValue("Attitude",1); - getField("Stabilization3Settings").setValue("Attitude",2); - getField("FlightModePosition").setValue("Manual",0); - getField("FlightModePosition").setValue("Manual",1); - getField("FlightModePosition").setValue("Manual",2); - getField("ChannelMax").setValue(2000,0); - getField("ChannelMax").setValue(2000,1); - getField("ChannelMax").setValue(2000,2); - getField("ChannelMax").setValue(2000,3); - getField("ChannelMax").setValue(2000,4); - getField("ChannelMax").setValue(2000,5); - getField("ChannelMax").setValue(2000,6); - getField("ChannelMax").setValue(2000,7); - getField("ChannelNeutral").setValue(1500,0); - getField("ChannelNeutral").setValue(1500,1); - getField("ChannelNeutral").setValue(1500,2); - getField("ChannelNeutral").setValue(1500,3); - getField("ChannelNeutral").setValue(1500,4); - getField("ChannelNeutral").setValue(1500,5); - getField("ChannelNeutral").setValue(1500,6); - getField("ChannelNeutral").setValue(1500,7); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -355,7 +238,57 @@ public class ManualControlSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelNeutral").setValue(1500,8); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelMax").setValue(2000,8); getField("ArmedTimeout").setValue(30000); + getField("ChannelGroups").setValue("None",0); + getField("ChannelGroups").setValue("None",1); + getField("ChannelGroups").setValue("None",2); + getField("ChannelGroups").setValue("None",3); + getField("ChannelGroups").setValue("None",4); + getField("ChannelGroups").setValue("None",5); + getField("ChannelGroups").setValue("None",6); + getField("ChannelGroups").setValue("None",7); + getField("ChannelGroups").setValue("None",8); + getField("ChannelNumber").setValue(0,0); + getField("ChannelNumber").setValue(0,1); + getField("ChannelNumber").setValue(0,2); + getField("ChannelNumber").setValue(0,3); + getField("ChannelNumber").setValue(0,4); + getField("ChannelNumber").setValue(0,5); + getField("ChannelNumber").setValue(0,6); + getField("ChannelNumber").setValue(0,7); + getField("ChannelNumber").setValue(0,8); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Rate",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Rate",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Rate",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Stabilized1",1); + getField("FlightModePosition").setValue("Stabilized2",2); } @@ -384,7 +317,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2B82102; + protected static final int OBJID = 0x24959BB0; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 9aa87d49e..76841d8ff 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -83,12 +83,37 @@ public class MixerSettings extends UAVDataObject { ThrottleCurve2ElemNames.add("100"); fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + List Curve2SourceElemNames = new ArrayList(); + Curve2SourceElemNames.add("0"); + List Curve2SourceEnumOptions = new ArrayList(); + Curve2SourceEnumOptions.add("Throttle"); + Curve2SourceEnumOptions.add("Roll"); + Curve2SourceEnumOptions.add("Pitch"); + Curve2SourceEnumOptions.add("Yaw"); + Curve2SourceEnumOptions.add("Collective"); + Curve2SourceEnumOptions.add("Accessory0"); + Curve2SourceEnumOptions.add("Accessory1"); + Curve2SourceEnumOptions.add("Accessory2"); + Curve2SourceEnumOptions.add("Accessory3"); + Curve2SourceEnumOptions.add("Accessory4"); + Curve2SourceEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Curve2Source", "", UAVObjectField.FieldType.ENUM, Curve2SourceElemNames, Curve2SourceEnumOptions) ); + List Mixer1TypeElemNames = new ArrayList(); Mixer1TypeElemNames.add("0"); List Mixer1TypeEnumOptions = new ArrayList(); Mixer1TypeEnumOptions.add("Disabled"); Mixer1TypeEnumOptions.add("Motor"); Mixer1TypeEnumOptions.add("Servo"); + Mixer1TypeEnumOptions.add("CameraRoll"); + Mixer1TypeEnumOptions.add("CameraPitch"); + Mixer1TypeEnumOptions.add("CameraYaw"); + Mixer1TypeEnumOptions.add("Accessory0"); + Mixer1TypeEnumOptions.add("Accessory1"); + Mixer1TypeEnumOptions.add("Accessory2"); + Mixer1TypeEnumOptions.add("Accessory3"); + Mixer1TypeEnumOptions.add("Accessory4"); + Mixer1TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); List Mixer1VectorElemNames = new ArrayList(); @@ -105,6 +130,15 @@ public class MixerSettings extends UAVDataObject { Mixer2TypeEnumOptions.add("Disabled"); Mixer2TypeEnumOptions.add("Motor"); Mixer2TypeEnumOptions.add("Servo"); + Mixer2TypeEnumOptions.add("CameraRoll"); + Mixer2TypeEnumOptions.add("CameraPitch"); + Mixer2TypeEnumOptions.add("CameraYaw"); + Mixer2TypeEnumOptions.add("Accessory0"); + Mixer2TypeEnumOptions.add("Accessory1"); + Mixer2TypeEnumOptions.add("Accessory2"); + Mixer2TypeEnumOptions.add("Accessory3"); + Mixer2TypeEnumOptions.add("Accessory4"); + Mixer2TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); List Mixer2VectorElemNames = new ArrayList(); @@ -121,6 +155,15 @@ public class MixerSettings extends UAVDataObject { Mixer3TypeEnumOptions.add("Disabled"); Mixer3TypeEnumOptions.add("Motor"); Mixer3TypeEnumOptions.add("Servo"); + Mixer3TypeEnumOptions.add("CameraRoll"); + Mixer3TypeEnumOptions.add("CameraPitch"); + Mixer3TypeEnumOptions.add("CameraYaw"); + Mixer3TypeEnumOptions.add("Accessory0"); + Mixer3TypeEnumOptions.add("Accessory1"); + Mixer3TypeEnumOptions.add("Accessory2"); + Mixer3TypeEnumOptions.add("Accessory3"); + Mixer3TypeEnumOptions.add("Accessory4"); + Mixer3TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); List Mixer3VectorElemNames = new ArrayList(); @@ -137,6 +180,15 @@ public class MixerSettings extends UAVDataObject { Mixer4TypeEnumOptions.add("Disabled"); Mixer4TypeEnumOptions.add("Motor"); Mixer4TypeEnumOptions.add("Servo"); + Mixer4TypeEnumOptions.add("CameraRoll"); + Mixer4TypeEnumOptions.add("CameraPitch"); + Mixer4TypeEnumOptions.add("CameraYaw"); + Mixer4TypeEnumOptions.add("Accessory0"); + Mixer4TypeEnumOptions.add("Accessory1"); + Mixer4TypeEnumOptions.add("Accessory2"); + Mixer4TypeEnumOptions.add("Accessory3"); + Mixer4TypeEnumOptions.add("Accessory4"); + Mixer4TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); List Mixer4VectorElemNames = new ArrayList(); @@ -153,6 +205,15 @@ public class MixerSettings extends UAVDataObject { Mixer5TypeEnumOptions.add("Disabled"); Mixer5TypeEnumOptions.add("Motor"); Mixer5TypeEnumOptions.add("Servo"); + Mixer5TypeEnumOptions.add("CameraRoll"); + Mixer5TypeEnumOptions.add("CameraPitch"); + Mixer5TypeEnumOptions.add("CameraYaw"); + Mixer5TypeEnumOptions.add("Accessory0"); + Mixer5TypeEnumOptions.add("Accessory1"); + Mixer5TypeEnumOptions.add("Accessory2"); + Mixer5TypeEnumOptions.add("Accessory3"); + Mixer5TypeEnumOptions.add("Accessory4"); + Mixer5TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); List Mixer5VectorElemNames = new ArrayList(); @@ -169,6 +230,15 @@ public class MixerSettings extends UAVDataObject { Mixer6TypeEnumOptions.add("Disabled"); Mixer6TypeEnumOptions.add("Motor"); Mixer6TypeEnumOptions.add("Servo"); + Mixer6TypeEnumOptions.add("CameraRoll"); + Mixer6TypeEnumOptions.add("CameraPitch"); + Mixer6TypeEnumOptions.add("CameraYaw"); + Mixer6TypeEnumOptions.add("Accessory0"); + Mixer6TypeEnumOptions.add("Accessory1"); + Mixer6TypeEnumOptions.add("Accessory2"); + Mixer6TypeEnumOptions.add("Accessory3"); + Mixer6TypeEnumOptions.add("Accessory4"); + Mixer6TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); List Mixer6VectorElemNames = new ArrayList(); @@ -185,6 +255,15 @@ public class MixerSettings extends UAVDataObject { Mixer7TypeEnumOptions.add("Disabled"); Mixer7TypeEnumOptions.add("Motor"); Mixer7TypeEnumOptions.add("Servo"); + Mixer7TypeEnumOptions.add("CameraRoll"); + Mixer7TypeEnumOptions.add("CameraPitch"); + Mixer7TypeEnumOptions.add("CameraYaw"); + Mixer7TypeEnumOptions.add("Accessory0"); + Mixer7TypeEnumOptions.add("Accessory1"); + Mixer7TypeEnumOptions.add("Accessory2"); + Mixer7TypeEnumOptions.add("Accessory3"); + Mixer7TypeEnumOptions.add("Accessory4"); + Mixer7TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); List Mixer7VectorElemNames = new ArrayList(); @@ -201,6 +280,15 @@ public class MixerSettings extends UAVDataObject { Mixer8TypeEnumOptions.add("Disabled"); Mixer8TypeEnumOptions.add("Motor"); Mixer8TypeEnumOptions.add("Servo"); + Mixer8TypeEnumOptions.add("CameraRoll"); + Mixer8TypeEnumOptions.add("CameraPitch"); + Mixer8TypeEnumOptions.add("CameraYaw"); + Mixer8TypeEnumOptions.add("Accessory0"); + Mixer8TypeEnumOptions.add("Accessory1"); + Mixer8TypeEnumOptions.add("Accessory2"); + Mixer8TypeEnumOptions.add("Accessory3"); + Mixer8TypeEnumOptions.add("Accessory4"); + Mixer8TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); List Mixer8VectorElemNames = new ArrayList(); @@ -211,6 +299,56 @@ public class MixerSettings extends UAVDataObject { Mixer8VectorElemNames.add("Yaw"); fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + List Mixer9TypeElemNames = new ArrayList(); + Mixer9TypeElemNames.add("0"); + List Mixer9TypeEnumOptions = new ArrayList(); + Mixer9TypeEnumOptions.add("Disabled"); + Mixer9TypeEnumOptions.add("Motor"); + Mixer9TypeEnumOptions.add("Servo"); + Mixer9TypeEnumOptions.add("CameraRoll"); + Mixer9TypeEnumOptions.add("CameraPitch"); + Mixer9TypeEnumOptions.add("CameraYaw"); + Mixer9TypeEnumOptions.add("Accessory0"); + Mixer9TypeEnumOptions.add("Accessory1"); + Mixer9TypeEnumOptions.add("Accessory2"); + Mixer9TypeEnumOptions.add("Accessory3"); + Mixer9TypeEnumOptions.add("Accessory4"); + Mixer9TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer9Type", "", UAVObjectField.FieldType.ENUM, Mixer9TypeElemNames, Mixer9TypeEnumOptions) ); + + List Mixer9VectorElemNames = new ArrayList(); + Mixer9VectorElemNames.add("ThrottleCurve1"); + Mixer9VectorElemNames.add("ThrottleCurve2"); + Mixer9VectorElemNames.add("Roll"); + Mixer9VectorElemNames.add("Pitch"); + Mixer9VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer9Vector", "", UAVObjectField.FieldType.INT8, Mixer9VectorElemNames, null) ); + + List Mixer10TypeElemNames = new ArrayList(); + Mixer10TypeElemNames.add("0"); + List Mixer10TypeEnumOptions = new ArrayList(); + Mixer10TypeEnumOptions.add("Disabled"); + Mixer10TypeEnumOptions.add("Motor"); + Mixer10TypeEnumOptions.add("Servo"); + Mixer10TypeEnumOptions.add("CameraRoll"); + Mixer10TypeEnumOptions.add("CameraPitch"); + Mixer10TypeEnumOptions.add("CameraYaw"); + Mixer10TypeEnumOptions.add("Accessory0"); + Mixer10TypeEnumOptions.add("Accessory1"); + Mixer10TypeEnumOptions.add("Accessory2"); + Mixer10TypeEnumOptions.add("Accessory3"); + Mixer10TypeEnumOptions.add("Accessory4"); + Mixer10TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer10Type", "", UAVObjectField.FieldType.ENUM, Mixer10TypeElemNames, Mixer10TypeEnumOptions) ); + + List Mixer10VectorElemNames = new ArrayList(); + Mixer10VectorElemNames.add("ThrottleCurve1"); + Mixer10VectorElemNames.add("ThrottleCurve2"); + Mixer10VectorElemNames.add("Roll"); + Mixer10VectorElemNames.add("Pitch"); + Mixer10VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer10Vector", "", UAVObjectField.FieldType.INT8, Mixer10VectorElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -261,15 +399,16 @@ public class MixerSettings extends UAVDataObject { getField("AccelTime").setValue(0); getField("DecelTime").setValue(0); getField("ThrottleCurve1").setValue(0,0); - getField("ThrottleCurve1").setValue(0.25,1); - getField("ThrottleCurve1").setValue(0.5,2); - getField("ThrottleCurve1").setValue(0.75,3); - getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve1").setValue(0,1); + getField("ThrottleCurve1").setValue(0,2); + getField("ThrottleCurve1").setValue(0,3); + getField("ThrottleCurve1").setValue(0,4); getField("ThrottleCurve2").setValue(0,0); getField("ThrottleCurve2").setValue(0.25,1); getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); + getField("Curve2Source").setValue("Throttle"); getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); @@ -318,6 +457,18 @@ public class MixerSettings extends UAVDataObject { getField("Mixer8Vector").setValue(0,2); getField("Mixer8Vector").setValue(0,3); getField("Mixer8Vector").setValue(0,4); + getField("Mixer9Type").setValue("Disabled"); + getField("Mixer9Vector").setValue(0,0); + getField("Mixer9Vector").setValue(0,1); + getField("Mixer9Vector").setValue(0,2); + getField("Mixer9Vector").setValue(0,3); + getField("Mixer9Vector").setValue(0,4); + getField("Mixer10Type").setValue("Disabled"); + getField("Mixer10Vector").setValue(0,0); + getField("Mixer10Vector").setValue(0,1); + getField("Mixer10Vector").setValue(0,2); + getField("Mixer10Vector").setValue(0,3); + getField("Mixer10Vector").setValue(0,4); } @@ -346,7 +497,7 @@ public class MixerSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4FAE374E; + protected static final int OBJID = 0x5D16D6C4; protected static final String NAME = "MixerSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index fbd405b40..106220a8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -156,7 +156,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF6A33F10; + protected static final int OBJID = 0x11CFB4E6; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index f16ddd199..3b09dd1f8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -136,7 +136,7 @@ public class NedAccel extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8E852CE8; + protected static final int OBJID = 0x7C7F5BC0; protected static final String NAME = "NedAccel"; protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index 2a09c2b40..dccd85d36 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -51,12 +51,23 @@ public class ObjectPersistence extends UAVDataObject { List fields = new ArrayList(); + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + List OperationElemNames = new ArrayList(); OperationElemNames.add("0"); List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("NOP"); OperationEnumOptions.add("Load"); OperationEnumOptions.add("Save"); OperationEnumOptions.add("Delete"); + OperationEnumOptions.add("FullErase"); + OperationEnumOptions.add("Completed"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -68,14 +79,6 @@ public class ObjectPersistence extends UAVDataObject { SelectionEnumOptions.add("AllObjects"); fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); - List ObjectIDElemNames = new ArrayList(); - ObjectIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); - - List InstanceIDElemNames = new ArrayList(); - InstanceIDElemNames.add("0"); - fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -106,7 +109,7 @@ public class ObjectPersistence extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; @@ -149,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0x22216832; + protected static final int OBJID = 0xF69AD8B8; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 444009f90..ac30ad4f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE0739636; + protected static final int OBJID = 0xF9691DA4; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 5cf51df71..2ff5a5586 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2FC4E5BA; + protected static final int OBJID = 0x33C9EAB4; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index 7164c0957..ddeacd8d4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -136,7 +136,7 @@ public class RateDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xBA41B51C; + protected static final int OBJID = 0xCE8C826; protected static final String NAME = "RateDesired"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java similarity index 61% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index 6af673930..a40b27e38 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Battery configuration information. + * Monitors which receiver channels have been active within the last second. * * @see The GNU Public License (GPL) Version 3 * @@ -39,40 +39,33 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Battery configuration information. +Monitors which receiver channels have been active within the last second. -generated from batterysettings.xml +generated from receiveractivity.xml **/ -public class BatterySettings extends UAVDataObject { +public class ReceiverActivity extends UAVDataObject { - public BatterySettings() { + public ReceiverActivity() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List BatteryVoltageElemNames = new ArrayList(); - BatteryVoltageElemNames.add("0"); - fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + List ActiveGroupElemNames = new ArrayList(); + ActiveGroupElemNames.add("0"); + List ActiveGroupEnumOptions = new ArrayList(); + ActiveGroupEnumOptions.add("PWM"); + ActiveGroupEnumOptions.add("PPM"); + ActiveGroupEnumOptions.add("DSM (MainPort)"); + ActiveGroupEnumOptions.add("DSM (FlexiPort)"); + ActiveGroupEnumOptions.add("S.Bus"); + ActiveGroupEnumOptions.add("GCS"); + ActiveGroupEnumOptions.add("None"); + fields.add( new UAVObjectField("ActiveGroup", "Channel Group", UAVObjectField.FieldType.ENUM, ActiveGroupElemNames, ActiveGroupEnumOptions) ); - List BatteryCapacityElemNames = new ArrayList(); - BatteryCapacityElemNames.add("0"); - fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); - - List BatteryTypeElemNames = new ArrayList(); - BatteryTypeElemNames.add("0"); - List BatteryTypeEnumOptions = new ArrayList(); - BatteryTypeEnumOptions.add("LiPo"); - BatteryTypeEnumOptions.add("A123"); - BatteryTypeEnumOptions.add("LiCo"); - BatteryTypeEnumOptions.add("LiFeSO4"); - BatteryTypeEnumOptions.add("None"); - fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); - - List CalibrationsElemNames = new ArrayList(); - CalibrationsElemNames.add("Voltage"); - CalibrationsElemNames.add("Current"); - fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + List ActiveChannelElemNames = new ArrayList(); + ActiveChannelElemNames.add("0"); + fields.add( new UAVObjectField("ActiveChannel", "channel", UAVObjectField.FieldType.UINT8, ActiveChannelElemNames, null) ); // Compute the number of bytes for this object @@ -97,13 +90,13 @@ public class BatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; metadata.gcsTelemetryUpdatePeriod = 0; metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; @@ -119,11 +112,8 @@ public class BatterySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("BatteryVoltage").setValue(11.1); - getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue("LiPo"); - getField("Calibrations").setValue(1,0); - getField("Calibrations").setValue(1,1); + getField("ActiveGroup").setValue("None"); + getField("ActiveChannel").setValue(255); } @@ -135,7 +125,7 @@ public class BatterySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - BatterySettings obj = new BatterySettings(); + ReceiverActivity obj = new ReceiverActivity(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -146,17 +136,17 @@ public class BatterySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + public ReceiverActivity GetInstance(UAVObjectManager objMngr, int instID) { - return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + return (ReceiverActivity)(objMngr.getObject(ReceiverActivity.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA5FF1D9A; - protected static final String NAME = "BatterySettings"; - protected static String DESCRIPTION = "Battery configuration information."; + protected static final int OBJID = 0x1E7C53DA; + protected static final String NAME = "ReceiverActivity"; + protected static String DESCRIPTION = "Monitors which receiver channels have been active within the last second."; protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 4e9f0b8b8..18cf6f4d6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -128,7 +128,7 @@ public class SonarAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1FDD844C; + protected static final int OBJID = 0x6C5A0CBC; protected static final String NAME = "SonarAltitude"; protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 8cba8a54c..32d2c735c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -75,6 +75,8 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("None"); StabilizationModeEnumOptions.add("Rate"); StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + StabilizationModeEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -150,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x41AA9DC2; + protected static final int OBJID = 0xDB8FFC3C; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index 74c480e1c..ab78bdc74 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -51,18 +51,6 @@ public class StabilizationSettings extends UAVDataObject { List fields = new ArrayList(); - List RollMaxElemNames = new ArrayList(); - RollMaxElemNames.add("0"); - fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); - - List PitchMaxElemNames = new ArrayList(); - PitchMaxElemNames.add("0"); - fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); - - List YawMaxElemNames = new ArrayList(); - YawMaxElemNames.add("0"); - fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); - List ManualRateElemNames = new ArrayList(); ManualRateElemNames.add("Roll"); ManualRateElemNames.add("Pitch"); @@ -75,23 +63,26 @@ public class StabilizationSettings extends UAVDataObject { MaximumRateElemNames.add("Yaw"); fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); - List RollRatePIElemNames = new ArrayList(); - RollRatePIElemNames.add("Kp"); - RollRatePIElemNames.add("Ki"); - RollRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + List RollRatePIDElemNames = new ArrayList(); + RollRatePIDElemNames.add("Kp"); + RollRatePIDElemNames.add("Ki"); + RollRatePIDElemNames.add("Kd"); + RollRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePID", "", UAVObjectField.FieldType.FLOAT32, RollRatePIDElemNames, null) ); - List PitchRatePIElemNames = new ArrayList(); - PitchRatePIElemNames.add("Kp"); - PitchRatePIElemNames.add("Ki"); - PitchRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + List PitchRatePIDElemNames = new ArrayList(); + PitchRatePIDElemNames.add("Kp"); + PitchRatePIDElemNames.add("Ki"); + PitchRatePIDElemNames.add("Kd"); + PitchRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePID", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIDElemNames, null) ); - List YawRatePIElemNames = new ArrayList(); - YawRatePIElemNames.add("Kp"); - YawRatePIElemNames.add("Ki"); - YawRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + List YawRatePIDElemNames = new ArrayList(); + YawRatePIDElemNames.add("Kp"); + YawRatePIDElemNames.add("Ki"); + YawRatePIDElemNames.add("Kd"); + YawRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePID", "", UAVObjectField.FieldType.FLOAT32, YawRatePIDElemNames, null) ); List RollPIElemNames = new ArrayList(); RollPIElemNames.add("Kp"); @@ -111,6 +102,45 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List GyroTauElemNames = new ArrayList(); + GyroTauElemNames.add("0"); + fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); + + List WeakLevelingKpElemNames = new ArrayList(); + WeakLevelingKpElemNames.add("0"); + fields.add( new UAVObjectField("WeakLevelingKp", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, WeakLevelingKpElemNames, null) ); + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List MaxAxisLockElemNames = new ArrayList(); + MaxAxisLockElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxAxisLockRateElemNames, null) ); + + List MaxWeakLevelingRateElemNames = new ArrayList(); + MaxWeakLevelingRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxWeakLevelingRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxWeakLevelingRateElemNames, null) ); + + List LowThrottleZeroIntegralElemNames = new ArrayList(); + LowThrottleZeroIntegralElemNames.add("0"); + List LowThrottleZeroIntegralEnumOptions = new ArrayList(); + LowThrottleZeroIntegralEnumOptions.add("FALSE"); + LowThrottleZeroIntegralEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LowThrottleZeroIntegral", "", UAVObjectField.FieldType.ENUM, LowThrottleZeroIntegralElemNames, LowThrottleZeroIntegralEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,24 +186,24 @@ public class StabilizationSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("RollMax").setValue(35); - getField("PitchMax").setValue(35); - getField("YawMax").setValue(35); getField("ManualRate").setValue(150,0); getField("ManualRate").setValue(150,1); getField("ManualRate").setValue(150,2); getField("MaximumRate").setValue(300,0); getField("MaximumRate").setValue(300,1); getField("MaximumRate").setValue(300,2); - getField("RollRatePI").setValue(0.0015,0); - getField("RollRatePI").setValue(0,1); - getField("RollRatePI").setValue(0.3,2); - getField("PitchRatePI").setValue(0.0015,0); - getField("PitchRatePI").setValue(0,1); - getField("PitchRatePI").setValue(0.3,2); - getField("YawRatePI").setValue(0.003,0); - getField("YawRatePI").setValue(0,1); - getField("YawRatePI").setValue(0.3,2); + getField("RollRatePID").setValue(0.002,0); + getField("RollRatePID").setValue(0,1); + getField("RollRatePID").setValue(0,2); + getField("RollRatePID").setValue(0.3,3); + getField("PitchRatePID").setValue(0.002,0); + getField("PitchRatePID").setValue(0,1); + getField("PitchRatePID").setValue(0,2); + getField("PitchRatePID").setValue(0.3,3); + getField("YawRatePID").setValue(0.0035,0); + getField("YawRatePID").setValue(0.0035,1); + getField("YawRatePID").setValue(0,2); + getField("YawRatePID").setValue(0.3,3); getField("RollPI").setValue(2,0); getField("RollPI").setValue(0,1); getField("RollPI").setValue(50,2); @@ -183,6 +213,15 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("GyroTau").setValue(0.005); + getField("WeakLevelingKp").setValue(0.1); + getField("RollMax").setValue(55); + getField("PitchMax").setValue(55); + getField("YawMax").setValue(35); + getField("MaxAxisLock").setValue(15); + getField("MaxAxisLockRate").setValue(2); + getField("MaxWeakLevelingRate").setValue(5); + getField("LowThrottleZeroIntegral").setValue("TRUE"); } @@ -211,7 +250,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE2147404; + protected static final int OBJID = 0x5F78C51E; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index e9313472c..458dd9d10 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -68,6 +68,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); + AlarmElemNames.add("BootFault"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -106,8 +107,8 @@ public class SystemAlarms extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 4000; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; metadata.loggingUpdatePeriod = 1000; @@ -137,6 +138,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",13); getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); + getField("Alarm").setValue("Uninitialised",16); } @@ -165,7 +167,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x89C3DCB2; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index 99bceb6ba..e3c2cf0b0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -51,6 +51,11 @@ public class SystemSettings extends UAVDataObject { List fields = new ArrayList(); + List GUIConfigDataElemNames = new ArrayList(); + GUIConfigDataElemNames.add("0"); + GUIConfigDataElemNames.add("1"); + fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); + List AirframeTypeElemNames = new ArrayList(); AirframeTypeElemNames.add("0"); List AirframeTypeEnumOptions = new ArrayList(); @@ -117,6 +122,8 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GUIConfigData").setValue(0,0); + getField("GUIConfigData").setValue(0,1); getField("AirframeType").setValue("FixedWing"); } @@ -146,7 +153,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x3875CEE; + protected static final int OBJID = 0x30BD5D7C; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 7c34360e9..d1c51d43f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -59,6 +59,10 @@ public class SystemStats extends UAVDataObject { HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + List IRQStackRemainingElemNames = new ArrayList(); + IRQStackRemainingElemNames.add("0"); + fields.add( new UAVObjectField("IRQStackRemaining", "bytes", UAVObjectField.FieldType.UINT16, IRQStackRemainingElemNames, null) ); + List CPULoadElemNames = new ArrayList(); CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); @@ -140,7 +144,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xAA26FFFA; + protected static final int OBJID = 0xD610A0F0; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 3ad065b5c..54825fafe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -65,6 +65,8 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("Com2UsbBridge"); + StackRemainingElemNames.add("Usb2ComBridge"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); @@ -81,11 +83,31 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("Stabilization"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("Com2UsbBridge"); + RunningElemNames.add("Usb2ComBridge"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("System"); + RunningTimeElemNames.add("Actuator"); + RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("TelemetryTx"); + RunningTimeElemNames.add("TelemetryTxPri"); + RunningTimeElemNames.add("TelemetryRx"); + RunningTimeElemNames.add("GPS"); + RunningTimeElemNames.add("ManualControl"); + RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("AHRSComms"); + RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("Guidance"); + RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("Com2UsbBridge"); + RunningTimeElemNames.add("Usb2ComBridge"); + fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -159,7 +181,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x50F599F0; + protected static final int OBJID = 0xE34A7C32; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index d1d47aebb..c2cf64d49 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,13 +28,14 @@ package org.openpilot.uavtalk.uavobjects; -//import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); @@ -45,19 +46,25 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); - objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new CameraDesired() ); + objMngr.registerObject( new CameraStabSettings() ); + objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); objMngr.registerObject( new FlightPlanSettings() ); objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightStatus() ); objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSReceiver() ); objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); @@ -68,6 +75,7 @@ public class UAVObjectsInitialize { objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new ReceiverActivity() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); @@ -75,7 +83,6 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); objMngr.registerObject( new TaskInfo() ); - objMngr.registerObject( new TelemetrySettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 649e6c122..97d038cfe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x48009C88; + protected static final int OBJID = 0x43007EB0; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 27f290898..f39fbd6de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x122F5E3A; + protected static final int OBJID = 0x25139D1A; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index 3adcad96b..acbdb43d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -132,7 +132,7 @@ public class WatchdogStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD646E910; + protected static final int OBJID = 0xA207FA7C; protected static final String NAME = "WatchdogStatus"; protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index e942b238f..dc593fd5f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -258,7 +258,7 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) outCode.replace(QString("$(INITFIELDS)"), initfields); // Write the java code - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->name + ".java", outCode ); if (!res) { cout << "Error: Could not write gcs output files" << endl; return false; From 4a38eac0db8f63a33f996407078dde58b59946cb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 5 Apr 2012 23:35:04 -0500 Subject: [PATCH 242/508] Small upgrades to teh android install --- androidgcs/.classpath | 1 + androidgcs/proguard.cfg | 2 +- androidgcs/res/layout/gcs_home.xml | 50 ++++++++---- .../androidgcs/OPTelemetryService.java | 79 ++++++++++++++++++- 4 files changed, 114 insertions(+), 18 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index eb33e4360..c88f96260 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -5,5 +5,6 @@ + diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg index 12dd0392c..ec78e7622 100644 --- a/androidgcs/proguard.cfg +++ b/androidgcs/proguard.cfg @@ -14,7 +14,7 @@ -keep public class * extends android.preference.Preference -keep public class com.android.vending.licensing.ILicensingService --keepclasseswithmembernames class * { +-keepclasseswithmembers class * { native ; } diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index e07f5b003..0ff427bcd 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -1,15 +1,37 @@ - - - - + + + + + + + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index ce90f5a48..bc711560d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -71,21 +71,25 @@ public class OPTelemetryService extends Service { stopSelf(msg.arg2); break; case MSG_CONNECT: - Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - //int connection_type = Integer.decode(prefs.getString("connection_type", "")); - int connection_type = 1; + int connection_type = Integer.decode(prefs.getString("connection_type", "")); switch(connection_type) { case 0: // No connection return; case 1: + Toast.makeText(getApplicationContext(), "Attempting fake connection", Toast.LENGTH_SHORT).show(); activeTelem = new FakeTelemetryThread(); break; case 2: + Toast.makeText(getApplicationContext(), "Attempting BT connection", Toast.LENGTH_SHORT).show(); activeTelem = new BTTelemetryThread(); break; case 3: + Toast.makeText(getApplicationContext(), "Attempting TCP connection", Toast.LENGTH_SHORT).show(); + activeTelem = new TcpTelemetryThread(); + break; + default: throw new Error("Unsupported"); } activeTelem.start(); @@ -329,6 +333,75 @@ public class OPTelemetryService extends Service { }; + private class TcpTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + TcpTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); + + TcpUAVTalk tcp = new TcpUAVTalk(OPTelemetryService.this); + for( int i = 0; i < 10; i++ ) { + if (DEBUG) Log.d(TAG, "Attempting network Connection"); + + tcp.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( tcp.getConnected() ) + break; + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } + } + if( ! tcp.getConnected() ) { + return; + } + + + if (DEBUG) Log.d(TAG, "Connected via network"); + + uavTalk = tcp.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while( !terminate ) { + if( !uavTalk.processInputStream() ) + break; + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); From 3445cafb0a34c5dfa2bda706b1343927edbef7e3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 10:22:38 -0500 Subject: [PATCH 243/508] Add TCP UAVTalk interface for android --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 84 +++++++++++++++++++ 1 file changed, 84 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java new file mode 100644 index 000000000..ad503757e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -0,0 +1,84 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.net.InetAddress; +import java.net.Socket; +import java.net.UnknownHostException; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.content.Context; +import android.util.Log; + +public class TcpUAVTalk { + private final String TAG = "TcpUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String IP_ADDRESS = "127.0.0.1"; + public final static int PORT = 9001; + + private UAVTalk uavTalk; + private boolean connected; + + public TcpUAVTalk(Context caller) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + + connected = false; + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !openTelemetryTcp(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + + private boolean openTelemetryTcp(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + + InetAddress serverAddr = null; + try { + serverAddr = InetAddress.getByName(IP_ADDRESS); + } catch (UnknownHostException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + Socket socket = null; + try { + socket = new Socket(serverAddr,PORT); + } catch (IOException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} From 3bcfeca77ce83993fb2aed42ac7270824810209a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 11:59:50 -0500 Subject: [PATCH 244/508] Enable some debugging statements --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 4 ++-- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 3 ++- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 +++++++++++------- 4 files changed, 16 insertions(+), 11 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index ad503757e..47074f968 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -17,7 +17,7 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "127.0.0.1"; + public final static String IP_ADDRESS = "10.21.18.120"; public final static int PORT = 9001; private UAVTalk uavTalk; @@ -47,7 +47,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); InetAddress serverAddr = null; try { diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..11e6cb2ca 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index daedcc85b..903b6b29f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -185,7 +185,8 @@ public class TelemetryMonitor extends Observable{ // Force update if not yet connected gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - + if (DEBUG) Log.d(TAG,"GCS Status: " + gcsStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"Flight Status: " + flightStatsObj.getField("Status").getValue()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 39c1f6ee7..5a3a9a1a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -433,6 +433,7 @@ public class UAVTalk extends Observable { rxCSPacket = rxbyte; if (rxCS != rxCSPacket) { // packet error - faulty CRC + if (DEBUG) Log.d(TAG,"Bad crc"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -441,11 +442,14 @@ public class UAVTalk extends Observable { if (rxPacketLength != (packetSize + 1)) { // packet error - // mismatched packet // size + if (DEBUG) Log.d(TAG,"Bad size"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } + if (DEBUG) Log.d(TAG,"Received"); + rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; @@ -500,8 +504,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - // System.out.println("Received object ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -517,8 +521,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - // System.out.println("Received object request: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object request: " + objId + " " + + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); } else { @@ -534,8 +538,8 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - // System.out.println("Received ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From beb75f22cf62cec49f12d352b59f82c32a180bcd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 12:06:36 -0500 Subject: [PATCH 245/508] Remove the TCHAIN_PREFIX flag from the OSX Makefile. No clue how that got merged in. --- flight/Revolution/Makefile.osx | 3 --- 1 file changed, 3 deletions(-) diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index e2c8ea694..a38bced0d 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -40,9 +40,6 @@ USE_BOOTLOADER ?= NO # Set to YES when using Code Sourcery toolchain CODE_SOURCERY ?= NO -# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- - # Remove command is different for Code Sourcery on Windows REMOVE_CMD ?= rm From aa99433310ada974ecfae473351818f7858b10a9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:42:19 -0500 Subject: [PATCH 246/508] Fix an insidious bug in the Android UAVObjectField unpack method for enums that was exposed by shuffling field orders. There goes 5 hours, FML. --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ad70630..286859e63 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -226,9 +226,9 @@ public class UAVObjectField { } case ENUM: { - List l = (List) data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - l.set(index, dataIn.get(index)); + l.set(index, dataIn.get()); } break; } From e9964668be5fcfa8962cb63c0181c82037d71785 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:49:57 -0500 Subject: [PATCH 247/508] Update objects and delete old UAVObjects --- .../uavtalk/uavobjects/AHRSCalibration.java | 252 ------------------ .../uavtalk/uavobjects/AHRSSettings.java | 178 ------------- .../uavtalk/uavobjects/AhrsStatus.java | 201 -------------- .../uavtalk/uavobjects/AttitudeRaw.java | 158 ----------- .../uavtalk/uavobjects/FlightStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 8 +- .../uavtalk/uavobjects/HomeLocation.java | 32 +-- .../uavtalk/uavobjects/HwSettings.java | 98 +++++-- .../uavobjects/ManualControlSettings.java | 4 +- .../uavtalk/uavobjects/MixerStatus.java | 10 +- .../uavtalk/uavobjects/NedAccel.java | 6 +- .../uavtalk/uavobjects/PositionActual.java | 8 +- .../uavtalk/uavobjects/PositionDesired.java | 8 +- .../uavtalk/uavobjects/SystemAlarms.java | 4 +- .../uavtalk/uavobjects/SystemStats.java | 14 +- .../uavtalk/uavobjects/TaskInfo.java | 17 +- .../uavobjects/UAVObjectsInitialize.java | 18 +- .../uavtalk/uavobjects/VelocityActual.java | 8 +- .../uavtalk/uavobjects/VelocityDesired.java | 8 +- 19 files changed, 153 insertions(+), 883 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java deleted file mode 100644 index 47d42991e..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ /dev/null @@ -1,252 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the calibration settings for the @ref AHRSCommsModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the calibration settings for the @ref AHRSCommsModule - -generated from ahrscalibration.xml - **/ -public class AHRSCalibration extends UAVDataObject { - - public AHRSCalibration() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List accel_biasElemNames = new ArrayList(); - accel_biasElemNames.add("X"); - accel_biasElemNames.add("Y"); - accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); - - List accel_scaleElemNames = new ArrayList(); - accel_scaleElemNames.add("X"); - accel_scaleElemNames.add("Y"); - accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); - - List accel_orthoElemNames = new ArrayList(); - accel_orthoElemNames.add("XY"); - accel_orthoElemNames.add("XZ"); - accel_orthoElemNames.add("YZ"); - fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); - - List accel_varElemNames = new ArrayList(); - accel_varElemNames.add("X"); - accel_varElemNames.add("Y"); - accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); - - List gyro_biasElemNames = new ArrayList(); - gyro_biasElemNames.add("X"); - gyro_biasElemNames.add("Y"); - gyro_biasElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); - - List gyro_scaleElemNames = new ArrayList(); - gyro_scaleElemNames.add("X"); - gyro_scaleElemNames.add("Y"); - gyro_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); - - List gyro_varElemNames = new ArrayList(); - gyro_varElemNames.add("X"); - gyro_varElemNames.add("Y"); - gyro_varElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); - - List gyro_tempcompfactorElemNames = new ArrayList(); - gyro_tempcompfactorElemNames.add("X"); - gyro_tempcompfactorElemNames.add("Y"); - gyro_tempcompfactorElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); - - List mag_biasElemNames = new ArrayList(); - mag_biasElemNames.add("X"); - mag_biasElemNames.add("Y"); - mag_biasElemNames.add("Z"); - fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); - - List mag_scaleElemNames = new ArrayList(); - mag_scaleElemNames.add("X"); - mag_scaleElemNames.add("Y"); - mag_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); - - List mag_varElemNames = new ArrayList(); - mag_varElemNames.add("X"); - mag_varElemNames.add("Y"); - mag_varElemNames.add("Z"); - fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); - - List vel_varElemNames = new ArrayList(); - vel_varElemNames.add("0"); - fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); - - List pos_varElemNames = new ArrayList(); - pos_varElemNames.add("0"); - fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); - - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("accel_bias").setValue(-73.5,0); - getField("accel_bias").setValue(-73.5,1); - getField("accel_bias").setValue(73.5,2); - getField("accel_scale").setValue(0.0359,0); - getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(0.0359,2); - getField("accel_ortho").setValue(0,0); - getField("accel_ortho").setValue(0,1); - getField("accel_ortho").setValue(0,2); - getField("accel_var").setValue(0.0005,0); - getField("accel_var").setValue(0.0005,1); - getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(28,0); - getField("gyro_bias").setValue(-28,1); - getField("gyro_bias").setValue(28,2); - getField("gyro_scale").setValue(-0.017,0); - getField("gyro_scale").setValue(0.017,1); - getField("gyro_scale").setValue(-0.017,2); - getField("gyro_var").setValue(0.0001,0); - getField("gyro_var").setValue(0.0001,1); - getField("gyro_var").setValue(0.0001,2); - getField("gyro_tempcompfactor").setValue(0,0); - getField("gyro_tempcompfactor").setValue(0,1); - getField("gyro_tempcompfactor").setValue(0,2); - getField("mag_bias").setValue(0,0); - getField("mag_bias").setValue(0,1); - getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(1,0); - getField("mag_scale").setValue(1,1); - getField("mag_scale").setValue(1,2); - getField("mag_var").setValue(50,0); - getField("mag_var").setValue(50,1); - getField("mag_var").setValue(50,2); - getField("vel_var").setValue(10); - getField("pos_var").setValue(0.04); - getField("measure_var").setValue("SET"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSCalibration obj = new AHRSCalibration(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xFD0EDFC4; - protected static final String NAME = "AHRSCalibration"; - protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java deleted file mode 100644 index 032dae775..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ /dev/null @@ -1,178 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - -generated from ahrssettings.xml - **/ -public class AHRSSettings extends UAVDataObject { - - public AHRSSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - - List AlgorithmElemNames = new ArrayList(); - AlgorithmElemNames.add("0"); - List AlgorithmEnumOptions = new ArrayList(); - AlgorithmEnumOptions.add("SIMPLE"); - AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); - AlgorithmEnumOptions.add("INSGPS_INDOOR"); - AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); - fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); - - List DownsamplingElemNames = new ArrayList(); - DownsamplingElemNames.add("0"); - fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); - - List BiasCorrectedRawElemNames = new ArrayList(); - BiasCorrectedRawElemNames.add("0"); - List BiasCorrectedRawEnumOptions = new ArrayList(); - BiasCorrectedRawEnumOptions.add("TRUE"); - BiasCorrectedRawEnumOptions.add("FALSE"); - fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); - getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); - getField("Downsampling").setValue(20); - getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue("TRUE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSSettings obj = new AHRSSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xF8591ED8; - protected static final String NAME = "AHRSSettings"; - protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java deleted file mode 100644 index 82e447a70..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ /dev/null @@ -1,201 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status for the @ref AHRSCommsModule, including communication errors - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status for the @ref AHRSCommsModule, including communication errors - -generated from ahrsstatus.xml - **/ -public class AhrsStatus extends UAVDataObject { - - public AhrsStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - - List SerialNumberElemNames = new ArrayList(); - SerialNumberElemNames.add("0"); - SerialNumberElemNames.add("1"); - SerialNumberElemNames.add("2"); - SerialNumberElemNames.add("3"); - SerialNumberElemNames.add("4"); - SerialNumberElemNames.add("5"); - SerialNumberElemNames.add("6"); - SerialNumberElemNames.add("7"); - fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); - - List CPULoadElemNames = new ArrayList(); - CPULoadElemNames.add("0"); - fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - - List IdleTimePerCyleElemNames = new ArrayList(); - IdleTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); - - List RunningTimePerCyleElemNames = new ArrayList(); - RunningTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); - - List DroppedUpdatesElemNames = new ArrayList(); - DroppedUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); - - List LinkRunningElemNames = new ArrayList(); - LinkRunningElemNames.add("0"); - List LinkRunningEnumOptions = new ArrayList(); - LinkRunningEnumOptions.add("FALSE"); - LinkRunningEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); - - List AhrsKickstartsElemNames = new ArrayList(); - AhrsKickstartsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); - - List AhrsCrcErrorsElemNames = new ArrayList(); - AhrsCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); - - List AhrsRetriesElemNames = new ArrayList(); - AhrsRetriesElemNames.add("0"); - fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); - - List AhrsInvalidPacketsElemNames = new ArrayList(); - AhrsInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); - - List OpCrcErrorsElemNames = new ArrayList(); - OpCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); - - List OpRetriesElemNames = new ArrayList(); - OpRetriesElemNames.add("0"); - fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); - - List OpInvalidPacketsElemNames = new ArrayList(); - OpInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AhrsStatus obj = new AhrsStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) - { - return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x706D1AB8; - protected static final String NAME = "AhrsStatus"; - protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java deleted file mode 100644 index b8c3aacb4..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - -generated from attituderaw.xml - **/ -public class AttitudeRaw extends UAVDataObject { - - public AttitudeRaw() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List gyrosElemNames = new ArrayList(); - gyrosElemNames.add("X"); - gyrosElemNames.add("Y"); - gyrosElemNames.add("Z"); - fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - - List accelsElemNames = new ArrayList(); - accelsElemNames.add("X"); - accelsElemNames.add("Y"); - accelsElemNames.add("Z"); - fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); - - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeRaw obj = new AttitudeRaw(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) - { - return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xDB722974; - protected static final String NAME = "AttitudeRaw"; - protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index d775b21e7..ac3812aa6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -66,8 +66,10 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("Stabilized1"); FlightModeEnumOptions.add("Stabilized2"); FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("AltitudeHold"); FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); + FlightModeEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -144,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x743DB13C; + protected static final int OBJID = 0x19B92D8; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 205384efe..5510a901d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -55,14 +55,14 @@ public class GuidanceSettings extends UAVDataObject { HorizontalPosPIElemNames.add("Kp"); HorizontalPosPIElemNames.add("Ki"); HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); List VerticalPosPIElemNames = new ArrayList(); VerticalPosPIElemNames.add("Kp"); @@ -87,11 +87,11 @@ public class GuidanceSettings extends UAVDataObject { List HorizontalVelMaxElemNames = new ArrayList(); HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); List VerticalVelMaxElemNames = new ArrayList(); VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); List GuidanceModeElemNames = new ArrayList(); GuidanceModeElemNames.add("0"); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 68abb3633..3f3b3d8dd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -63,24 +63,6 @@ public class HomeLocation extends UAVDataObject { AltitudeElemNames.add("0"); fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - List ECEFElemNames = new ArrayList(); - ECEFElemNames.add("0"); - ECEFElemNames.add("1"); - ECEFElemNames.add("2"); - fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); - - List RNEElemNames = new ArrayList(); - RNEElemNames.add("0"); - RNEElemNames.add("1"); - RNEElemNames.add("2"); - RNEElemNames.add("3"); - RNEElemNames.add("4"); - RNEElemNames.add("5"); - RNEElemNames.add("6"); - RNEElemNames.add("7"); - RNEElemNames.add("8"); - fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); - List BeElemNames = new ArrayList(); BeElemNames.add("0"); BeElemNames.add("1"); @@ -146,18 +128,6 @@ public class HomeLocation extends UAVDataObject { getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); - getField("ECEF").setValue(0,0); - getField("ECEF").setValue(0,1); - getField("ECEF").setValue(0,2); - getField("RNE").setValue(0,0); - getField("RNE").setValue(0,1); - getField("RNE").setValue(0,2); - getField("RNE").setValue(0,3); - getField("RNE").setValue(0,4); - getField("RNE").setValue(0,5); - getField("RNE").setValue(0,6); - getField("RNE").setValue(0,7); - getField("RNE").setValue(0,8); getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); @@ -191,7 +161,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5BB3AEFC; + protected static final int OBJID = 0x6185DC6E; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index 83b7ae7b6..f56982e69 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -89,31 +89,70 @@ public class HwSettings extends UAVDataObject { CC_FlexiPortEnumOptions.add("ComBridge"); fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); - List OP_RcvrPortElemNames = new ArrayList(); - OP_RcvrPortElemNames.add("0"); - List OP_RcvrPortEnumOptions = new ArrayList(); - OP_RcvrPortEnumOptions.add("Disabled"); - OP_RcvrPortEnumOptions.add("PWM"); - OP_RcvrPortEnumOptions.add("PPM"); - OP_RcvrPortEnumOptions.add("DSM2"); - OP_RcvrPortEnumOptions.add("DSMX (10bit)"); - OP_RcvrPortEnumOptions.add("DSMX (11bit)"); - OP_RcvrPortEnumOptions.add("Debug"); - fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + List RV_RcvrPortElemNames = new ArrayList(); + RV_RcvrPortElemNames.add("0"); + List RV_RcvrPortEnumOptions = new ArrayList(); + RV_RcvrPortEnumOptions.add("Disabled"); + RV_RcvrPortEnumOptions.add("PWM"); + RV_RcvrPortEnumOptions.add("PPM"); + RV_RcvrPortEnumOptions.add("PPM+Outputs"); + RV_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("RV_RcvrPort", "function", UAVObjectField.FieldType.ENUM, RV_RcvrPortElemNames, RV_RcvrPortEnumOptions) ); - List OP_MainPortElemNames = new ArrayList(); - OP_MainPortElemNames.add("0"); - List OP_MainPortEnumOptions = new ArrayList(); - OP_MainPortEnumOptions.add("Disabled"); - OP_MainPortEnumOptions.add("Telemetry"); - fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + List RV_AuxPortElemNames = new ArrayList(); + RV_AuxPortElemNames.add("0"); + List RV_AuxPortEnumOptions = new ArrayList(); + RV_AuxPortEnumOptions.add("Disabled"); + RV_AuxPortEnumOptions.add("Telemetry"); + RV_AuxPortEnumOptions.add("DSM2"); + RV_AuxPortEnumOptions.add("DSMX (10bit)"); + RV_AuxPortEnumOptions.add("DSMX (11bit)"); + RV_AuxPortEnumOptions.add("ComAux"); + RV_AuxPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxPortElemNames, RV_AuxPortEnumOptions) ); - List OP_FlexiPortElemNames = new ArrayList(); - OP_FlexiPortElemNames.add("0"); - List OP_FlexiPortEnumOptions = new ArrayList(); - OP_FlexiPortEnumOptions.add("Disabled"); - OP_FlexiPortEnumOptions.add("GPS"); - fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + List RV_AuxSBusPortElemNames = new ArrayList(); + RV_AuxSBusPortElemNames.add("0"); + List RV_AuxSBusPortEnumOptions = new ArrayList(); + RV_AuxSBusPortEnumOptions.add("Disabled"); + RV_AuxSBusPortEnumOptions.add("S.Bus"); + RV_AuxSBusPortEnumOptions.add("DSM2"); + RV_AuxSBusPortEnumOptions.add("DSMX (10bit)"); + RV_AuxSBusPortEnumOptions.add("DSMX (11bit)"); + RV_AuxSBusPortEnumOptions.add("ComAux"); + RV_AuxSBusPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxSBusPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxSBusPortElemNames, RV_AuxSBusPortEnumOptions) ); + + List RV_FlexiPortElemNames = new ArrayList(); + RV_FlexiPortElemNames.add("0"); + List RV_FlexiPortEnumOptions = new ArrayList(); + RV_FlexiPortEnumOptions.add("Disabled"); + RV_FlexiPortEnumOptions.add("I2C"); + RV_FlexiPortEnumOptions.add("DSM2"); + RV_FlexiPortEnumOptions.add("DSMX (10bit)"); + RV_FlexiPortEnumOptions.add("DSMX (11bit)"); + RV_FlexiPortEnumOptions.add("ComAux"); + RV_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_FlexiPort", "function", UAVObjectField.FieldType.ENUM, RV_FlexiPortElemNames, RV_FlexiPortEnumOptions) ); + + List RV_TelemetryPortElemNames = new ArrayList(); + RV_TelemetryPortElemNames.add("0"); + List RV_TelemetryPortEnumOptions = new ArrayList(); + RV_TelemetryPortEnumOptions.add("Disabled"); + RV_TelemetryPortEnumOptions.add("Telemetry"); + RV_TelemetryPortEnumOptions.add("ComAux"); + RV_TelemetryPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_TelemetryPort", "function", UAVObjectField.FieldType.ENUM, RV_TelemetryPortElemNames, RV_TelemetryPortEnumOptions) ); + + List RV_GPSPortElemNames = new ArrayList(); + RV_GPSPortElemNames.add("0"); + List RV_GPSPortEnumOptions = new ArrayList(); + RV_GPSPortEnumOptions.add("Disabled"); + RV_GPSPortEnumOptions.add("Telemetry"); + RV_GPSPortEnumOptions.add("GPS"); + RV_GPSPortEnumOptions.add("ComAux"); + RV_GPSPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_GPSPort", "function", UAVObjectField.FieldType.ENUM, RV_GPSPortElemNames, RV_GPSPortEnumOptions) ); List TelemetrySpeedElemNames = new ArrayList(); TelemetrySpeedElemNames.add("0"); @@ -180,6 +219,7 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("TxPID"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -237,9 +277,12 @@ public class HwSettings extends UAVDataObject { getField("CC_RcvrPort").setValue("PWM"); getField("CC_MainPort").setValue("Disabled"); getField("CC_FlexiPort").setValue("Disabled"); - getField("OP_RcvrPort").setValue("PWM"); - getField("OP_MainPort").setValue("Telemetry"); - getField("OP_FlexiPort").setValue("GPS"); + getField("RV_RcvrPort").setValue("PWM"); + getField("RV_AuxPort").setValue("Disabled"); + getField("RV_AuxSBusPort").setValue("Disabled"); + getField("RV_FlexiPort").setValue("Disabled"); + getField("RV_TelemetryPort").setValue("Telemetry"); + getField("RV_GPSPort").setValue("GPS"); getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); @@ -251,6 +294,7 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",2); getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); + getField("OptionalModules").setValue("Disabled",5); getField("DSMxBind").setValue(0); } @@ -280,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2EE6575A; + protected static final int OBJID = 0x4730375C; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index bb846695d..c8f460bc4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -181,8 +181,10 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("Stabilized1"); FlightModePositionEnumOptions.add("Stabilized2"); FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("AltitudeHold"); FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); + FlightModePositionEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); @@ -317,7 +319,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x24959BB0; + protected static final int OBJID = 0x59C4551C; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 106220a8c..80e3b15bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -83,6 +83,14 @@ public class MixerStatus extends UAVDataObject { Mixer8ElemNames.add("0"); fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + List Mixer9ElemNames = new ArrayList(); + Mixer9ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer9", "", UAVObjectField.FieldType.FLOAT32, Mixer9ElemNames, null) ); + + List Mixer10ElemNames = new ArrayList(); + Mixer10ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer10", "", UAVObjectField.FieldType.FLOAT32, Mixer10ElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,7 +164,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x11CFB4E6; + protected static final int OBJID = 0x124E28A; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 3b09dd1f8..1629a19d2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -53,15 +53,15 @@ public class NedAccel extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index ac30ad4f5..184098a16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -53,15 +53,15 @@ public class PositionActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF9691DA4; + protected static final int OBJID = 0xFA9E2D42; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 2ff5a5586..123ca58af 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -53,15 +53,15 @@ public class PositionDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x33C9EAB4; + protected static final int OBJID = 0x778DBE24; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 458dd9d10..bc4bf0625 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -61,6 +61,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); AlarmElemNames.add("AHRSComms"); @@ -139,6 +140,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); + getField("Alarm").setValue("Uninitialised",17); } @@ -167,7 +169,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x737ADCF2; + protected static final int OBJID = 0x9C7CBFE; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index d1c51d43f..26d01f2a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -55,6 +55,18 @@ public class SystemStats extends UAVDataObject { FlightTimeElemNames.add("0"); fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + List EventSystemWarningIDElemNames = new ArrayList(); + EventSystemWarningIDElemNames.add("0"); + fields.add( new UAVObjectField("EventSystemWarningID", "uavoid", UAVObjectField.FieldType.UINT32, EventSystemWarningIDElemNames, null) ); + + List ObjectManagerCallbackIDElemNames = new ArrayList(); + ObjectManagerCallbackIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerCallbackID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerCallbackIDElemNames, null) ); + + List ObjectManagerQueueIDElemNames = new ArrayList(); + ObjectManagerQueueIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerQueueID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerQueueIDElemNames, null) ); + List HeapRemainingElemNames = new ArrayList(); HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); @@ -144,7 +156,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD610A0F0; + protected static final int OBJID = 0x364D1406; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 54825fafe..eefcef6d9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -55,36 +55,42 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("System"); StackRemainingElemNames.add("Actuator"); StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("Sensors"); StackRemainingElemNames.add("TelemetryTx"); StackRemainingElemNames.add("TelemetryTxPri"); StackRemainingElemNames.add("TelemetryRx"); StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); - StackRemainingElemNames.add("AHRSComms"); StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("AltitudeHold"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("PathPlanner"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); + StackRemainingElemNames.add("OveroSync"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); RunningElemNames.add("System"); RunningElemNames.add("Actuator"); RunningElemNames.add("Attitude"); + RunningElemNames.add("Sensors"); RunningElemNames.add("TelemetryTx"); RunningElemNames.add("TelemetryTxPri"); RunningElemNames.add("TelemetryRx"); RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); - RunningElemNames.add("AHRSComms"); RunningElemNames.add("Stabilization"); + RunningElemNames.add("AltitudeHold"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("PathPlanner"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); + RunningElemNames.add("OveroSync"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); @@ -94,18 +100,21 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("System"); RunningTimeElemNames.add("Actuator"); RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("Sensors"); RunningTimeElemNames.add("TelemetryTx"); RunningTimeElemNames.add("TelemetryTxPri"); RunningTimeElemNames.add("TelemetryRx"); RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); - RunningTimeElemNames.add("AHRSComms"); RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("AltitudeHold"); RunningTimeElemNames.add("Guidance"); RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("PathPlanner"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); + RunningTimeElemNames.add("OveroSync"); fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); @@ -181,7 +190,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE34A7C32; + protected static final int OBJID = 0x498F54BA; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index c2cf64d49..823643130 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -35,15 +35,15 @@ public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new Accels() ); objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); - objMngr.registerObject( new AHRSCalibration() ); - objMngr.registerObject( new AHRSSettings() ); - objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AltHoldSmoothed() ); + objMngr.registerObject( new AltitudeHoldDesired() ); + objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); - objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); @@ -62,16 +62,23 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GPSVelocity() ); + objMngr.registerObject( new Gyros() ); + objMngr.registerObject( new GyrosBias() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PathDesired() ); objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); @@ -82,10 +89,13 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); + objMngr.registerObject( new Waypoint() ); + objMngr.registerObject( new WaypointActive() ); } catch (Exception e) { e.printStackTrace(); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 97d038cfe..2a8cd3754 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -53,15 +53,15 @@ public class VelocityActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x43007EB0; + protected static final int OBJID = 0x5A08F61A; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index f39fbd6de..436ef6448 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -53,15 +53,15 @@ public class VelocityDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x25139D1A; + protected static final int OBJID = 0x9E946992; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; From 02f9452193da60e0b1bc82883775bd8218170417 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:12:45 -0500 Subject: [PATCH 248/508] Update fake telemetry object --- .../org/openpilot/androidgcs/OPTelemetryService.java | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index bc711560d..074049d79 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -222,18 +222,6 @@ public class OPTelemetryService extends Service { homeLocation.getField("Latitude").setDouble(379420315); homeLocation.getField("Longitude").setDouble(-88330078); - homeLocation.getField("ECEF").setDouble(497665694,0); - homeLocation.getField("ECEF").setDouble(-77336320,1); - homeLocation.getField("ECEF").setDouble(390037169,2); - homeLocation.getField("RNE").setDouble(-0.60757166,0); - homeLocation.getField("RNE").setDouble(0.09441550,1); - homeLocation.getField("RNE").setDouble(0.78863323,2); - homeLocation.getField("RNE").setDouble(0.15355512,3); - homeLocation.getField("RNE").setDouble(0.98814011,4); - homeLocation.getField("RNE").setDouble(0,5); - homeLocation.getField("RNE").setDouble(-0.77928013,6); - homeLocation.getField("RNE").setDouble(0.12109867,7); - homeLocation.getField("RNE").setDouble(-0.61486387,8); homeLocation.getField("Be").setDouble(26702.78710938,0); homeLocation.getField("Be").setDouble(-1468.33605957,1); homeLocation.getField("Be").setDouble(34181.78515625,2); From 574c2000b66831df0a5b01d59ca559814e26eaaa Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:38:49 -0500 Subject: [PATCH 249/508] Lower all the debugging levels again --- .../org/openpilot/androidgcs/OPTelemetryService.java | 2 +- androidgcs/src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../src/org/openpilot/uavtalk/TelemetryMonitor.java | 10 ++++++++-- androidgcs/src/org/openpilot/uavtalk/UAVTalk.java | 10 ++++------ 4 files changed, 14 insertions(+), 10 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 074049d79..1a4b61eb8 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -33,7 +33,7 @@ public class OPTelemetryService extends Service { // Logging settings private final String TAG = "OPTelemetryService"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 11e6cb2ca..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 903b6b29f..87a0cdc70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -13,7 +13,7 @@ import android.util.Log; public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -204,6 +204,8 @@ public class TelemetryMonitor extends Observable{ Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats reset"); + // Update stats object gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); @@ -214,6 +216,8 @@ public class TelemetryMonitor extends Observable{ field = gcsStatsObj.getField("TxRetries"); field.setDouble(field.getDouble() + telStats.txRetries); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats updated"); + // Check for a connection timeout boolean connectionTimeout; if ( telStats.rxObjects > 0 ) @@ -296,8 +300,10 @@ public class TelemetryMonitor extends Observable{ objects_updated = false; setChanged(); } + + if (DEBUG) Log.d(TAG, "processStatsUpdates() - before notify"); notifyObservers(); - + if (DEBUG) Log.d(TAG, "processStatsUpdates() - after notify"); } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 5a3a9a1a5..9cdd11ccb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -504,8 +504,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -521,7 +520,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - System.out.println("Received object request: " + objId + " " + + if (DEBUG) Log.d(TAG,"Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -538,8 +537,7 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From 1a63c21be904ece1baea2bd9054b0274133d938b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 11:04:35 -0500 Subject: [PATCH 250/508] First step to fixing metat data representation for android --- .../org/openpilot/uavtalk/UAVMetaObject.java | 46 ++++-------- .../src/org/openpilot/uavtalk/UAVObject.java | 70 +++++++------------ .../org/openpilot/uavtalk/UAVObjectField.java | 48 ++++++++++++- 3 files changed, 85 insertions(+), 79 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 7aab176ef..c57b6c2fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -13,43 +13,25 @@ public class UAVMetaObject extends UAVObject { ownMetadata = new Metadata(); - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flags = 0; // TODO: Fix flags ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; ownMetadata.loggingUpdatePeriod = 0; - // Setup fields - List boolEnum = new ArrayList(); - boolEnum.add("False"); - boolEnum.add("True"); - List updateModeEnum = new ArrayList(); - updateModeEnum.add("Periodic"); - updateModeEnum.add("On Change"); - updateModeEnum.add("Manual"); - updateModeEnum.add("Never"); + List modesBitField = new ArrayList(); + modesBitField.add("FlightReadOnly"); + modesBitField.add("GCSReadOnly"); + modesBitField.add("FlightTelemetryAcked"); + modesBitField.add("GCSTelemetryAcked"); + modesBitField.add("FlightUpdatePeriodic"); + modesBitField.add("FlightUpdateOnChange"); + modesBitField.add("GCSUpdatePeriodic"); + modesBitField.add("GCSUpdateOnChange"); - List accessModeEnum = new ArrayList(); - accessModeEnum.add("Read/Write"); - accessModeEnum.add("Read Only"); - - List fields = new ArrayList(); - fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); - fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); - fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("Logging Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); int numBytes = 0; ListIterator li = fields.listIterator(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 940b076a5..20d4cb02a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -120,17 +120,10 @@ public abstract class UAVObject { * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** - * Automatically update object at periodic - * intervals - */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** - * Manually update object, by calling the updated() - * function - */ - UPDATEMODE_NEVER - /** Object is never updated */ + UPDATEMODE_THROTTLED /** Object is updated on change, but not more often than the interval time */ }; /** @@ -140,47 +133,32 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - /** - * Access mode - */ - public enum Acked { - FALSE, TRUE - }; - public final class Metadata { - public AccessMode flightAccess; /** - * Defines the access level for the local flight transactions (readonly - * and readwrite) + * Object metadata, each object has a meta object that holds its metadata. The metadata define + * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ - public AccessMode gcsAccess; - /** - * Defines the access level for the local GCS transactions (readonly and - * readwrite) - */ - public Acked flightTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode flightTelemetryUpdateMode; - /** Update mode used by the autopilot (UpdateMode) */ + public int flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + + /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ public int flightTelemetryUpdatePeriod; - /** - * Update period used by the autopilot (only if telemetry mode is - * PERIODIC) - */ - public Acked gcsTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode gcsTelemetryUpdateMode; - /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; + + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; - /** Update mode used by the logging module (UpdateMode) */ public int loggingUpdatePeriod; /** * Update period used by the logging module (only if logging mode is diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 286859e63..c2965f6cc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -7,7 +7,7 @@ import java.util.List; public class UAVObjectField { - public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, BITFIELD, STRING }; public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { List elementNames = new ArrayList(); @@ -56,6 +56,8 @@ public class UAVObjectField { return "float32"; case ENUM: return "enum"; + case BITFIELD: + return "bitfield"; case STRING: return "string"; default: @@ -144,6 +146,11 @@ public class UAVObjectField { for (int index = 0; index < numElements; ++index) dataOut.put((Byte) l.get(index)); break; + case BITFIELD: + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } case STRING: // TODO: Implement strings throw new Error("Strings not yet implemented"); @@ -224,6 +231,16 @@ public class UAVObjectField { } break; } + case BITFIELD: + { + List l = (List) this.data; + for (int index = 0 ; index < numElements; ++index) { + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); + } + break; + } case ENUM: { List l = (List) this.data; @@ -275,6 +292,9 @@ public class UAVObjectField { return options.get(val); } + case BITFIELD: + return ((List) data).get(index).intValue(); + case STRING: { //throw new Exception("Shit I should do this"); @@ -354,6 +374,12 @@ public class UAVObjectField { l.set(index, val); break; } + case BITFIELD: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case STRING: { //throw new Exception("Sorry I haven't implemented strings yet"); @@ -404,6 +430,8 @@ public class UAVObjectField { return true; case ENUM: return false; + case BITFIELD: + return true; case STRING: return false; default: @@ -430,6 +458,8 @@ public class UAVObjectField { return false; case ENUM: return true; + case BITFIELD: + return false; case STRING: return true; default: @@ -493,6 +523,12 @@ public class UAVObjectField { ((ArrayList) data).add((float) 0); } break; + case BITFIELD: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case ENUM: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { @@ -549,6 +585,10 @@ public class UAVObjectField { data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; + case BITFIELD: + data = (Object) new ArrayList(this.numElements); + numBytesPerElement = 1; + break; case STRING: data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; @@ -614,6 +654,12 @@ public class UAVObjectField { if(num > 4294967295L) return 4294967295L; return num; + case BITFIELD: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; } return num; From 62bb4601c5876b2e0c5aeeb78a30f4c503ea13fd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 12:49:34 -0500 Subject: [PATCH 251/508] Finish porting the meta data changes from GCS and update all the UAVOs --- .../src/org/openpilot/uavtalk/Telemetry.java | 29 +- .../openpilot/uavtalk/TelemetryMonitor.java | 37 ++- .../src/org/openpilot/uavtalk/UAVObject.java | 194 +++++++++++- .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../uavtalk/uavobjects/AccessoryDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorCommand.java | 23 +- .../uavtalk/uavobjects/ActuatorDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorSettings.java | 280 +----------------- .../uavtalk/uavobjects/AttitudeActual.java | 23 +- .../uavtalk/uavobjects/AttitudeSettings.java | 23 +- .../uavtalk/uavobjects/BaroAltitude.java | 23 +- .../uavtalk/uavobjects/CameraDesired.java | 23 +- .../uavobjects/CameraStabSettings.java | 23 +- .../uavtalk/uavobjects/FaultSettings.java | 23 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 23 +- .../uavobjects/FlightBatterySettings.java | 36 ++- .../uavobjects/FlightBatteryState.java | 30 +- .../uavtalk/uavobjects/FlightPlanControl.java | 23 +- .../uavobjects/FlightPlanSettings.java | 23 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 23 +- .../uavtalk/uavobjects/FlightStatus.java | 26 +- .../uavobjects/FlightTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GCSReceiver.java | 27 +- .../uavtalk/uavobjects/GCSTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GPSPosition.java | 23 +- .../uavtalk/uavobjects/GPSSatellites.java | 23 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 23 +- .../uavtalk/uavobjects/GuidanceSettings.java | 211 ------------- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 44 +-- .../uavtalk/uavobjects/I2CStats.java | 23 +- .../uavobjects/ManualControlCommand.java | 23 +- .../uavobjects/ManualControlSettings.java | 48 ++- .../uavtalk/uavobjects/MixerSettings.java | 23 +- .../uavtalk/uavobjects/MixerStatus.java | 23 +- .../uavtalk/uavobjects/NedAccel.java | 23 +- .../uavtalk/uavobjects/ObjectPersistence.java | 26 +- .../uavtalk/uavobjects/PositionActual.java | 23 +- .../uavtalk/uavobjects/PositionDesired.java | 147 --------- .../uavtalk/uavobjects/RateDesired.java | 23 +- .../uavtalk/uavobjects/ReceiverActivity.java | 23 +- .../uavtalk/uavobjects/SonarAltitude.java | 23 +- .../uavobjects/StabilizationDesired.java | 26 +- .../uavobjects/StabilizationSettings.java | 78 ++++- .../uavtalk/uavobjects/SystemAlarms.java | 29 +- .../uavtalk/uavobjects/SystemSettings.java | 34 ++- .../uavtalk/uavobjects/SystemStats.java | 23 +- .../uavtalk/uavobjects/TaskInfo.java | 40 +-- .../uavobjects/UAVObjectsInitialize.java | 21 +- .../uavtalk/uavobjects/VelocityActual.java | 23 +- .../uavtalk/uavobjects/VelocityDesired.java | 23 +- .../uavtalk/uavobjects/WatchdogStatus.java | 23 +- .../templates/uavobjecttemplate.java | 23 +- 53 files changed, 880 insertions(+), 1244 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..2ee5ab9a4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -10,8 +10,6 @@ import java.util.Queue; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.UAVObject.Acked; - import android.util.Log; public class Telemetry { @@ -20,7 +18,7 @@ public class Telemetry { public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -50,7 +48,7 @@ public class Telemetry { boolean allInstances; boolean objRequest; int retriesRemaining; - Acked acked; + boolean acked; } ; /** @@ -249,7 +247,7 @@ public class Telemetry { // Setup object depending on update mode int eventMask; - if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) { // Set update period setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); @@ -260,7 +258,7 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) { // Set update period setUpdatePeriod(obj, 0); @@ -271,7 +269,11 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_THROTTLED ) + { + // TODO + } + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) { // Set update period setUpdatePeriod(obj, 0); @@ -282,13 +284,6 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) - { - // Set update period - setUpdatePeriod(obj, 0); - // Disconnect from object - connectToObjectInstances(obj, 0); - } } /** @@ -360,10 +355,10 @@ public class Telemetry { } else { - utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + utalk.sendObject(transInfo.obj, transInfo.acked, transInfo.allInstances); } // Start timer if a response is expected - if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + if ( transInfo.objRequest || transInfo.acked ) { transTimerSetPeriod(REQ_TIMEOUT_MS); } @@ -476,7 +471,7 @@ public class Telemetry { transInfo.obj = objInfo.obj; transInfo.allInstances = objInfo.allInstances; transInfo.retriesRemaining = MAX_RETRIES; - transInfo.acked = metadata.gcsTelemetryAcked; + transInfo.acked = metadata.GetGcsTelemetryAcked(); if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) { transInfo.objRequest = false; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 87a0cdc70..d1d7a9c44 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -76,27 +76,24 @@ public class TelemetryMonitor extends Observable{ List instList = objListIterator.next(); UAVObject obj = instList.get(0); UAVObject.Metadata mdata = obj.getMetadata(); - if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + if ( obj.isMetadata() ) { - if ( obj.isMetadata() ) - { - queue.add(obj); - } - else /* Data object */ - { - UAVDataObject dobj = (UAVDataObject) obj; - if ( dobj.isSettings() ) - { - queue.add(obj); - } - else - { - if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) - { - queue.add(obj); - } - } - } + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.GetFlightTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } } } // Start retrieving diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 20d4cb02a..28c279040 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -133,7 +133,15 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - public final class Metadata { + public final static int UAVOBJ_ACCESS_SHIFT = 0; + public final static int UAVOBJ_GCS_ACCESS_SHIFT = 1; + public final static int UAVOBJ_TELEMETRY_ACKED_SHIFT = 2; + public final static int UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT = 3; + public final static int UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT = 4; + public final static int UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT = 6; + public final static int UAVOBJ_UPDATE_MODE_MASK = 0x3; + + public final static class Metadata { /** * Object metadata, each object has a meta object that holds its metadata. The metadata define * properties for each object and can be used by multiple modules (e.g. telemetry and logger) @@ -164,6 +172,190 @@ public abstract class UAVObject { * Update period used by the logging module (only if logging mode is * PERIODIC) */ + + /** + * @brief Helper method for metadata accessors + * @param var The starting value + * @param shift The offset of these bits + * @param value The new value + * @param mask The mask of these bits + * @return + */ + private void SET_BITS(int shift, int value, int mask) { + this.flags = (this.flags & ~(mask << shift)) | (value << shift); + } + + /** + * Get the UAVObject metadata access member + * \return the access type + */ + public AccessMode GetFlightAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata access member + * \param[in] mode The access mode + */ + public void SetFlightAccess(Metadata metadata, AccessMode mode) + { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata GCS access member + * \return the GCS access type + */ + public AccessMode GetGcsAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata GCS access member + * \param[in] mode The access mode + */ + public void SetGcsAccess(Metadata metadata, AccessMode mode) { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_GCS_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetFlightTelemetryAcked() { + return (((this.flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1) == 1); + } + + /** + * Set the UAVObject metadata telemetry acked member + * \param[in] val The telemetry acked boolean + */ + public void SetFlightTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Get the UAVObject metadata GCS telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetGcsTelemetryAcked() { + return ((this.flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1) == 1; + } + + /** + * Set the UAVObject metadata GCS telemetry acked member + * \param[in] val The GCS telemetry acked boolean + */ + public void SetGcsTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static AccessMode AccessModeEnum(int num) { + switch(num) { + case 0: + return AccessMode.ACCESS_READONLY; + case 1: + return AccessMode.ACCESS_READWRITE; + } + return AccessMode.ACCESS_READONLY; + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int AccessModeNum(AccessMode e) { + switch(e) { + case ACCESS_READONLY: + return 0; + case ACCESS_READWRITE: + return 1; + } + return 0; + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static UpdateMode UpdateModeEnum(int num) { + switch(num) { + case 0: + return UpdateMode.UPDATEMODE_MANUAL; + case 1: + return UpdateMode.UPDATEMODE_PERIODIC; + case 2: + return UpdateMode.UPDATEMODE_ONCHANGE; + default: + return UpdateMode.UPDATEMODE_THROTTLED; + } + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int UpdateModeNum(UpdateMode e) { + switch(e) { + case UPDATEMODE_MANUAL: + return 0; + case UPDATEMODE_PERIODIC: + return 1; + case UPDATEMODE_ONCHANGE: + return 2; + case UPDATEMODE_THROTTLED: + return 3; + } + return 0; + } + + /** + * Get the UAVObject metadata telemetry update mode + * \return the telemetry update mode + */ + public UpdateMode GetFlightTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The telemetry update mode + */ + public void SetFlightTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Get the UAVObject metadata GCS telemetry update mode + * \param[in] metadata The metadata object + * \return the GCS telemetry update mode + */ + public UpdateMode GetGcsTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata GCS telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry update mode + */ + public void SetGcsTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + }; public UAVObject(int objID, Boolean isSingleInst, String name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c2965f6cc..3ed221079 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -314,7 +314,7 @@ public class UAVObjectField { // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.GetGcsAccess() == UAVObject.AccessMode.ACCESS_READWRITE ) { switch (type) { diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java index 13c63dfdd..4b7c875a7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -78,18 +78,17 @@ public class AccessoryDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index 08f2ebefe..0120e0ce7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -99,18 +99,17 @@ public class ActuatorCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index 03ff1985c..a00517906 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -98,18 +98,17 @@ public class ActuatorDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 71b0bb49f..2257da346 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -97,246 +97,6 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("Channel9"); - FixedWingRoll1EnumOptions.add("Channel10"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("Channel9"); - FixedWingRoll2EnumOptions.add("Channel10"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("Channel9"); - FixedWingPitch1EnumOptions.add("Channel10"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("Channel9"); - FixedWingPitch2EnumOptions.add("Channel10"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYaw1ElemNames = new ArrayList(); - FixedWingYaw1ElemNames.add("0"); - List FixedWingYaw1EnumOptions = new ArrayList(); - FixedWingYaw1EnumOptions.add("Channel1"); - FixedWingYaw1EnumOptions.add("Channel2"); - FixedWingYaw1EnumOptions.add("Channel3"); - FixedWingYaw1EnumOptions.add("Channel4"); - FixedWingYaw1EnumOptions.add("Channel5"); - FixedWingYaw1EnumOptions.add("Channel6"); - FixedWingYaw1EnumOptions.add("Channel7"); - FixedWingYaw1EnumOptions.add("Channel8"); - FixedWingYaw1EnumOptions.add("Channel9"); - FixedWingYaw1EnumOptions.add("Channel10"); - FixedWingYaw1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); - - List FixedWingYaw2ElemNames = new ArrayList(); - FixedWingYaw2ElemNames.add("0"); - List FixedWingYaw2EnumOptions = new ArrayList(); - FixedWingYaw2EnumOptions.add("Channel1"); - FixedWingYaw2EnumOptions.add("Channel2"); - FixedWingYaw2EnumOptions.add("Channel3"); - FixedWingYaw2EnumOptions.add("Channel4"); - FixedWingYaw2EnumOptions.add("Channel5"); - FixedWingYaw2EnumOptions.add("Channel6"); - FixedWingYaw2EnumOptions.add("Channel7"); - FixedWingYaw2EnumOptions.add("Channel8"); - FixedWingYaw2EnumOptions.add("Channel9"); - FixedWingYaw2EnumOptions.add("Channel10"); - FixedWingYaw2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("Channel9"); - FixedWingThrottleEnumOptions.add("Channel10"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("Channel9"); - VTOLMotorNEnumOptions.add("Channel10"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("Channel9"); - VTOLMotorNEEnumOptions.add("Channel10"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("Channel9"); - VTOLMotorEEnumOptions.add("Channel10"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("Channel9"); - VTOLMotorSEEnumOptions.add("Channel10"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("Channel9"); - VTOLMotorSEnumOptions.add("Channel10"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("Channel9"); - VTOLMotorSWEnumOptions.add("Channel10"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("Channel9"); - VTOLMotorWEnumOptions.add("Channel10"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("Channel9"); - VTOLMotorNWEnumOptions.add("Channel10"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -398,18 +158,17 @@ public class ActuatorSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -454,21 +213,6 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,7); getField("ChannelMin").setValue(1000,8); getField("ChannelMin").setValue(1000,9); - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw1").setValue("None"); - getField("FixedWingYaw2").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -518,7 +262,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF2875746; + protected static final int OBJID = 0x7D555646; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 7c9272cad..b117e501a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -102,18 +102,17 @@ public class AttitudeActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 100; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 3034a99ad..9bcce7bf3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -130,18 +130,17 @@ public class AttitudeSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index ecde53985..cd649f84c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -86,18 +86,17 @@ public class BaroAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java index 7a36ec1ea..34c23e612 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -86,18 +86,17 @@ public class CameraDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java index a8e03df32..0b2f3b3f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -125,18 +125,17 @@ public class CameraStabSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index b22b8185e..8da58f793 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -85,18 +85,17 @@ public class FaultSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 71c681bd2..58fadcee5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -152,18 +152,17 @@ public class FirmwareIAPObj extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java index a3bc23eb3..850f64103 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -80,9 +80,12 @@ public class FlightBatterySettings extends UAVDataObject { fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); List SensorTypeElemNames = new ArrayList(); - SensorTypeElemNames.add("0"); + SensorTypeElemNames.add("BatteryCurrent"); + SensorTypeElemNames.add("BatteryVoltage"); + SensorTypeElemNames.add("BoardVoltage"); List SensorTypeEnumOptions = new ArrayList(); - SensorTypeEnumOptions.add("None"); + SensorTypeEnumOptions.add("Disabled"); + SensorTypeEnumOptions.add("Enabled"); fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); @@ -108,18 +111,17 @@ public class FlightBatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -137,7 +139,9 @@ public class FlightBatterySettings extends UAVDataObject { getField("SensorCalibrations").setValue(1,1); getField("Type").setValue("LiPo"); getField("NbCells").setValue(3); - getField("SensorType").setValue("None"); + getField("SensorType").setValue("Disabled",0); + getField("SensorType").setValue("Disabled",1); + getField("SensorType").setValue("Disabled",2); } @@ -166,7 +170,7 @@ public class FlightBatterySettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF172BB18; + protected static final int OBJID = 0x94AC6AD2; protected static final String NAME = "FlightBatterySettings"; protected static String DESCRIPTION = "Flight Battery configuration."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index 82fcfae47..d54648ad5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -59,6 +59,10 @@ public class FlightBatteryState extends UAVDataObject { CurrentElemNames.add("0"); fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + List BoardSupplyVoltageElemNames = new ArrayList(); + BoardSupplyVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BoardSupplyVoltage", "V", UAVObjectField.FieldType.FLOAT32, BoardSupplyVoltageElemNames, null) ); + List PeakCurrentElemNames = new ArrayList(); PeakCurrentElemNames.add("0"); fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); @@ -98,18 +102,17 @@ public class FlightBatteryState extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -122,6 +125,7 @@ public class FlightBatteryState extends UAVDataObject { { getField("Voltage").setValue(0); getField("Current").setValue(0); + getField("BoardSupplyVoltage").setValue(0); getField("PeakCurrent").setValue(0); getField("AvgCurrent").setValue(0); getField("ConsumedEnergy").setValue(0); @@ -154,7 +158,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8C0D756; + protected static final int OBJID = 0xD2083596; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index dbe959f96..cdea28a0f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -82,18 +82,17 @@ public class FlightPlanControl extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 6fc39a26e..184bbd1b7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -78,18 +78,17 @@ public class FlightPlanSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 7b78bce71..8aa152789 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -119,18 +119,17 @@ public class FlightPlanStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index ac3812aa6..38697e573 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -70,6 +70,7 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); FlightModeEnumOptions.add("PathPlanner"); + FlightModeEnumOptions.add("RTH"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -95,18 +96,17 @@ public class FlightStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -146,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x19B92D8; + protected static final int OBJID = 0x884FEF66; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index 403ea1d5e..3a042f52e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -103,18 +103,17 @@ public class FlightTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java index 3cb3811ae..05fa87efb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -58,6 +58,8 @@ public class GCSReceiver extends UAVDataObject { ChannelElemNames.add("3"); ChannelElemNames.add("4"); ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); @@ -83,18 +85,17 @@ public class GCSReceiver extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -133,7 +134,7 @@ public class GCSReceiver extends UAVDataObject { } // Constants - protected static final int OBJID = 0xCC7E2BBC; + protected static final int OBJID = 0xCC7E1470; protected static final String NAME = "GCSReceiver"; protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index b32f551ce..754272c8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -103,18 +103,17 @@ public class GCSTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.gcsTelemetryUpdatePeriod = 5000; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 5000; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 5f4e20b46..c2c8544a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -123,18 +123,17 @@ public class GPSPosition extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index bb331132d..0f5b0161a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -154,18 +154,17 @@ public class GPSSatellites extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5aa4df7bf..7095aa18e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -98,18 +98,17 @@ public class GPSTime extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java deleted file mode 100644 index 5510a901d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ /dev/null @@ -1,211 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref GuidanceModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref GuidanceModule - -generated from guidancesettings.xml - **/ -public class GuidanceSettings extends UAVDataObject { - - public GuidanceSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List HorizontalPosPIElemNames = new ArrayList(); - HorizontalPosPIElemNames.add("Kp"); - HorizontalPosPIElemNames.add("Ki"); - HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); - - List HorizontalVelPIDElemNames = new ArrayList(); - HorizontalVelPIDElemNames.add("Kp"); - HorizontalVelPIDElemNames.add("Ki"); - HorizontalVelPIDElemNames.add("Kd"); - HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - - List VerticalPosPIElemNames = new ArrayList(); - VerticalPosPIElemNames.add("Kp"); - VerticalPosPIElemNames.add("Ki"); - VerticalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); - - List VerticalVelPIDElemNames = new ArrayList(); - VerticalVelPIDElemNames.add("Kp"); - VerticalVelPIDElemNames.add("Ki"); - VerticalVelPIDElemNames.add("Kd"); - VerticalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - - List MaxRollPitchElemNames = new ArrayList(); - MaxRollPitchElemNames.add("0"); - fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - List HorizontalVelMaxElemNames = new ArrayList(); - HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); - - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("HorizontalPosPI").setValue(0.1,0); - getField("HorizontalPosPI").setValue(0.001,1); - getField("HorizontalPosPI").setValue(300,2); - getField("HorizontalVelPID").setValue(0.05,0); - getField("HorizontalVelPID").setValue(0.002,1); - getField("HorizontalVelPID").setValue(0,2); - getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalPosPI").setValue(0.1,0); - getField("VerticalPosPI").setValue(0.001,1); - getField("VerticalPosPI").setValue(200,2); - getField("VerticalVelPID").setValue(0.1,0); - getField("VerticalVelPID").setValue(0,1); - getField("VerticalVelPID").setValue(0,2); - getField("VerticalVelPID").setValue(0,3); - getField("MaxRollPitch").setValue(10); - getField("UpdatePeriod").setValue(100); - getField("HorizontalVelMax").setValue(300); - getField("VerticalVelMax").setValue(150); - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("ThrottleControl").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - GuidanceSettings obj = new GuidanceSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x6EA79FB4; - protected static final String NAME = "GuidanceSettings"; - protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 3f3b3d8dd..0cd45db1b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -103,18 +103,17 @@ public class HomeLocation extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index f56982e69..9d8113846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -190,14 +190,6 @@ public class HwSettings extends UAVDataObject { ComUsbBridgeSpeedEnumOptions.add("115200"); fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); - List USB_DeviceTypeElemNames = new ArrayList(); - USB_DeviceTypeElemNames.add("0"); - List USB_DeviceTypeEnumOptions = new ArrayList(); - USB_DeviceTypeEnumOptions.add("HID-only"); - USB_DeviceTypeEnumOptions.add("HID+VCP"); - USB_DeviceTypeEnumOptions.add("VCP-only"); - fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); - List USB_HIDPortElemNames = new ArrayList(); USB_HIDPortElemNames.add("0"); List USB_HIDPortEnumOptions = new ArrayList(); @@ -219,7 +211,12 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("Airspeed"); OptionalModulesElemNames.add("TxPID"); + OptionalModulesElemNames.add("VtolPathFollower"); + OptionalModulesElemNames.add("FixedWingPathFollower"); + OptionalModulesElemNames.add("Battery"); + OptionalModulesElemNames.add("Overo"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -252,18 +249,17 @@ public class HwSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -286,7 +282,6 @@ public class HwSettings extends UAVDataObject { getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); - getField("USB_DeviceType").setValue("HID-only"); getField("USB_HIDPort").setValue("USBTelemetry"); getField("USB_VCPPort").setValue("Disabled"); getField("OptionalModules").setValue("Disabled",0); @@ -295,6 +290,11 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); getField("OptionalModules").setValue("Disabled",5); + getField("OptionalModules").setValue("Disabled",6); + getField("OptionalModules").setValue("Disabled",7); + getField("OptionalModules").setValue("Disabled",8); + getField("OptionalModules").setValue("Disabled",9); + getField("OptionalModules").setValue("Disabled",10); getField("DSMxBind").setValue(0); } @@ -324,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4730375C; + protected static final int OBJID = 0x5D950E50; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index abd8f41f6..a09e4404d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -177,18 +177,17 @@ public class I2CStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 6ac5a1b2c..5ce51c245 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -113,18 +113,17 @@ public class ManualControlCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c8f460bc4..47ebbc230 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,6 +51,10 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); + List DeadbandElemNames = new ArrayList(); + DeadbandElemNames.add("0"); + fields.add( new UAVObjectField("Deadband", "%", UAVObjectField.FieldType.FLOAT32, DeadbandElemNames, null) ); + List ChannelMinElemNames = new ArrayList(); ChannelMinElemNames.add("Throttle"); ChannelMinElemNames.add("Roll"); @@ -146,6 +150,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("Attitude"); Stabilization1SettingsEnumOptions.add("AxisLock"); Stabilization1SettingsEnumOptions.add("WeakLeveling"); + Stabilization1SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -158,6 +163,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("Attitude"); Stabilization2SettingsEnumOptions.add("AxisLock"); Stabilization2SettingsEnumOptions.add("WeakLeveling"); + Stabilization2SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -170,6 +176,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("Attitude"); Stabilization3SettingsEnumOptions.add("AxisLock"); Stabilization3SettingsEnumOptions.add("WeakLeveling"); + Stabilization3SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -185,8 +192,21 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); FlightModePositionEnumOptions.add("PathPlanner"); + FlightModePositionEnumOptions.add("RTH"); + FlightModePositionEnumOptions.add("Land"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + List FlightModeNumberElemNames = new ArrayList(); + FlightModeNumberElemNames.add("0"); + fields.add( new UAVObjectField("FlightModeNumber", "", UAVObjectField.FieldType.UINT8, FlightModeNumberElemNames, null) ); + + List FailsafeBehaviorElemNames = new ArrayList(); + FailsafeBehaviorElemNames.add("0"); + List FailsafeBehaviorEnumOptions = new ArrayList(); + FailsafeBehaviorEnumOptions.add("None"); + FailsafeBehaviorEnumOptions.add("RTH"); + fields.add( new UAVObjectField("FailsafeBehavior", "", UAVObjectField.FieldType.ENUM, FailsafeBehaviorElemNames, FailsafeBehaviorEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -210,18 +230,17 @@ public class ManualControlSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -232,6 +251,7 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Deadband").setValue(0); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -291,6 +311,8 @@ public class ManualControlSettings extends UAVDataObject { getField("FlightModePosition").setValue("Manual",0); getField("FlightModePosition").setValue("Stabilized1",1); getField("FlightModePosition").setValue("Stabilized2",2); + getField("FlightModeNumber").setValue(3); + getField("FailsafeBehavior").setValue("None"); } @@ -319,7 +341,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x59C4551C; + protected static final int OBJID = 0x6C188320; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 76841d8ff..094d91545 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -372,18 +372,17 @@ public class MixerSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 80e3b15bf..1f767c5ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -114,18 +114,17 @@ public class MixerStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 1629a19d2..6d09a799e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -86,18 +86,17 @@ public class NedAccel extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10001; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10001; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index dccd85d36..42a65e3ab 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -68,6 +68,7 @@ public class ObjectPersistence extends UAVDataObject { OperationEnumOptions.add("Delete"); OperationEnumOptions.add("FullErase"); OperationEnumOptions.add("Completed"); + OperationEnumOptions.add("Error"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -102,18 +103,17 @@ public class ObjectPersistence extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF69AD8B8; + protected static final int OBJID = 0x99C63292; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 184098a16..1c87c21c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -86,18 +86,17 @@ public class PositionActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 1000; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java deleted file mode 100644 index 123ca58af..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ /dev/null @@ -1,147 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - -generated from positiondesired.xml - **/ -public class PositionDesired extends UAVDataObject { - - public PositionDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - PositionDesired obj = new PositionDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) - { - return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x778DBE24; - protected static final String NAME = "PositionDesired"; - protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index ddeacd8d4..51f7faa7d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -86,18 +86,17 @@ public class RateDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index a40b27e38..15391ce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -90,18 +90,17 @@ public class ReceiverActivity extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 18cf6f4d6..1a5679d6a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -78,18 +78,17 @@ public class SonarAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 32d2c735c..8ca5df722 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -77,6 +77,7 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("Attitude"); StabilizationModeEnumOptions.add("AxisLock"); StabilizationModeEnumOptions.add("WeakLeveling"); + StabilizationModeEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -102,18 +103,17 @@ public class StabilizationDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDB8FFC3C; + protected static final int OBJID = 0xDE1EAAD6; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index ab78bdc74..cc2c69e8f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -102,6 +102,31 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List VbarSensitivityElemNames = new ArrayList(); + VbarSensitivityElemNames.add("Roll"); + VbarSensitivityElemNames.add("Pitch"); + VbarSensitivityElemNames.add("Yaw"); + fields.add( new UAVObjectField("VbarSensitivity", "frac", UAVObjectField.FieldType.FLOAT32, VbarSensitivityElemNames, null) ); + + List VbarRollPIElemNames = new ArrayList(); + VbarRollPIElemNames.add("Kp"); + VbarRollPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarRollPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarRollPIElemNames, null) ); + + List VbarPitchPIElemNames = new ArrayList(); + VbarPitchPIElemNames.add("Kp"); + VbarPitchPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarPitchPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarPitchPIElemNames, null) ); + + List VbarYawPIElemNames = new ArrayList(); + VbarYawPIElemNames.add("Kp"); + VbarYawPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarYawPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarYawPIElemNames, null) ); + + List VbarTauElemNames = new ArrayList(); + VbarTauElemNames.add("0"); + fields.add( new UAVObjectField("VbarTau", "sec", UAVObjectField.FieldType.FLOAT32, VbarTauElemNames, null) ); + List GyroTauElemNames = new ArrayList(); GyroTauElemNames.add("0"); fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); @@ -122,6 +147,21 @@ public class StabilizationSettings extends UAVDataObject { YawMaxElemNames.add("0"); fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + List VbarGyroSuppressElemNames = new ArrayList(); + VbarGyroSuppressElemNames.add("0"); + fields.add( new UAVObjectField("VbarGyroSuppress", "%", UAVObjectField.FieldType.INT8, VbarGyroSuppressElemNames, null) ); + + List VbarPiroCompElemNames = new ArrayList(); + VbarPiroCompElemNames.add("0"); + List VbarPiroCompEnumOptions = new ArrayList(); + VbarPiroCompEnumOptions.add("FALSE"); + VbarPiroCompEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("VbarPiroComp", "", UAVObjectField.FieldType.ENUM, VbarPiroCompElemNames, VbarPiroCompEnumOptions) ); + + List VbarMaxAngleElemNames = new ArrayList(); + VbarMaxAngleElemNames.add("0"); + fields.add( new UAVObjectField("VbarMaxAngle", "deg", UAVObjectField.FieldType.UINT8, VbarMaxAngleElemNames, null) ); + List MaxAxisLockElemNames = new ArrayList(); MaxAxisLockElemNames.add("0"); fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); @@ -164,18 +204,17 @@ public class StabilizationSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -213,11 +252,24 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("VbarSensitivity").setValue(0.5,0); + getField("VbarSensitivity").setValue(0.5,1); + getField("VbarSensitivity").setValue(0.5,2); + getField("VbarRollPI").setValue(0.005,0); + getField("VbarRollPI").setValue(0.002,1); + getField("VbarPitchPI").setValue(0.005,0); + getField("VbarPitchPI").setValue(0.002,1); + getField("VbarYawPI").setValue(0.005,0); + getField("VbarYawPI").setValue(0.002,1); + getField("VbarTau").setValue(0.5); getField("GyroTau").setValue(0.005); getField("WeakLevelingKp").setValue(0.1); getField("RollMax").setValue(55); getField("PitchMax").setValue(55); getField("YawMax").setValue(35); + getField("VbarGyroSuppress").setValue(30); + getField("VbarPiroComp").setValue("FALSE"); + getField("VbarMaxAngle").setValue(10); getField("MaxAxisLock").setValue(15); getField("MaxAxisLockRate").setValue(2); getField("MaxWeakLevelingRate").setValue(5); @@ -250,7 +302,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5F78C51E; + protected static final int OBJID = 0xBBC337D4; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index bc4bf0625..3b34763fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -56,7 +56,6 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("StackOverflow"); AlarmElemNames.add("CPUOverload"); AlarmElemNames.add("EventSystem"); - AlarmElemNames.add("SDCard"); AlarmElemNames.add("Telemetry"); AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); @@ -64,12 +63,12 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); - AlarmElemNames.add("AHRSComms"); AlarmElemNames.add("Battery"); AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); AlarmElemNames.add("BootFault"); + AlarmElemNames.add("Power"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -101,18 +100,17 @@ public class SystemAlarms extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -140,7 +138,6 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); - getField("Alarm").setValue("Uninitialised",17); } @@ -169,7 +166,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9C7CBFE; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index e3c2cf0b0..bffbced31 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -54,6 +54,8 @@ public class SystemSettings extends UAVDataObject { List GUIConfigDataElemNames = new ArrayList(); GUIConfigDataElemNames.add("0"); GUIConfigDataElemNames.add("1"); + GUIConfigDataElemNames.add("2"); + GUIConfigDataElemNames.add("3"); fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); List AirframeTypeElemNames = new ArrayList(); @@ -75,6 +77,9 @@ public class SystemSettings extends UAVDataObject { AirframeTypeEnumOptions.add("OctoCoaxX"); AirframeTypeEnumOptions.add("HexaCoax"); AirframeTypeEnumOptions.add("Tri"); + AirframeTypeEnumOptions.add("GroundVehicleCar"); + AirframeTypeEnumOptions.add("GroundVehicleDifferential"); + AirframeTypeEnumOptions.add("GroundVehicleMotorcycle"); fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); @@ -100,18 +105,17 @@ public class SystemSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -124,7 +128,9 @@ public class SystemSettings extends UAVDataObject { { getField("GUIConfigData").setValue(0,0); getField("GUIConfigData").setValue(0,1); - getField("AirframeType").setValue("FixedWing"); + getField("GUIConfigData").setValue(0,2); + getField("GUIConfigData").setValue(0,3); + getField("AirframeType").setValue("QuadX"); } @@ -153,7 +159,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30BD5D7C; + protected static final int OBJID = 0xC72A326E; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 26d01f2a0..888474261 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -106,18 +106,17 @@ public class SystemStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index eefcef6d9..9f530e6a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -62,11 +62,12 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("Airspeed"); StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("AltitudeHold"); - StackRemainingElemNames.add("Guidance"); - StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("PathPlanner"); + StackRemainingElemNames.add("PathFollower"); + StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); StackRemainingElemNames.add("OveroSync"); @@ -83,11 +84,12 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); + RunningElemNames.add("Airspeed"); RunningElemNames.add("Stabilization"); RunningElemNames.add("AltitudeHold"); - RunningElemNames.add("Guidance"); - RunningElemNames.add("FlightPlan"); RunningElemNames.add("PathPlanner"); + RunningElemNames.add("PathFollower"); + RunningElemNames.add("FlightPlan"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); RunningElemNames.add("OveroSync"); @@ -107,11 +109,12 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("Airspeed"); RunningTimeElemNames.add("Stabilization"); RunningTimeElemNames.add("AltitudeHold"); - RunningTimeElemNames.add("Guidance"); - RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("PathPlanner"); + RunningTimeElemNames.add("PathFollower"); + RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); RunningTimeElemNames.add("OveroSync"); @@ -140,18 +143,17 @@ public class TaskInfo extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -190,7 +192,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x498F54BA; + protected static final int OBJID = 0xB81CD2AE; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 823643130..7968c37c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -45,11 +45,15 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new AttitudeSimulated() ); + objMngr.registerObject( new BaroAirspeed() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); objMngr.registerObject( new CameraStabSettings() ); objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FixedWingPathFollowerSettings() ); + objMngr.registerObject( new FixedWingPathFollowerStatus() ); objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); @@ -61,38 +65,45 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSSettings() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GPSVelocity() ); objMngr.registerObject( new Gyros() ); objMngr.registerObject( new GyrosBias() ); - objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); - objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new MagBias() ); objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); - objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new OveroSyncSettings() ); + objMngr.registerObject( new OveroSyncStats() ); objMngr.registerObject( new PathDesired() ); + objMngr.registerObject( new PathPlannerSettings() ); + objMngr.registerObject( new PipXSettings() ); + objMngr.registerObject( new PipXStatus() ); objMngr.registerObject( new PositionActual() ); - objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); objMngr.registerObject( new ReceiverActivity() ); + objMngr.registerObject( new RevoCalibration() ); + objMngr.registerObject( new RevoSettings() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); - objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new VtolPathFollowerSettings() ); objMngr.registerObject( new WatchdogStatus() ); objMngr.registerObject( new Waypoint() ); objMngr.registerObject( new WaypointActive() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 2a8cd3754..a545bca16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -86,18 +86,17 @@ public class VelocityActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 436ef6448..f506a594c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -86,18 +86,17 @@ public class VelocityDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index acbdb43d1..94e85f57b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -82,18 +82,17 @@ public class WatchdogStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 64e2461f5..1283f03cb 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -74,18 +74,17 @@ $(FIELDSINIT) */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - - metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - - metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(FLIGHTACCESS)) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(GCSACCESS)) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE)) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE)) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; } From 4233c7da0da1da2efd929b658f958a13ce34272f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 13:08:47 -0500 Subject: [PATCH 252/508] Forgot to initialize the fields for metadata --- androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index c57b6c2fe..98a3bf8df 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -27,7 +27,8 @@ public class UAVMetaObject extends UAVObject { modesBitField.add("FlightUpdateOnChange"); modesBitField.add("GCSUpdatePeriodic"); modesBitField.add("GCSUpdateOnChange"); - + + List fields = new ArrayList(); fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); From cfb9f1277e3beefcfc77d9eb67141a3a9aac0584 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 13:49:16 -0500 Subject: [PATCH 253/508] Catch invalid number decoding to cover cases where there is no IP address. --- .../src/org/openpilot/androidgcs/OPTelemetryService.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 1a4b61eb8..917dfb116 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -72,8 +72,14 @@ public class OPTelemetryService extends Service { break; case MSG_CONNECT: terminate = false; + int connection_type; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + try { + connection_type = Integer.decode(prefs.getString("connection_type", "")); + } catch (NumberFormatException e) { + connection_type = 0; + } + switch(connection_type) { case 0: // No connection return; From 4d114060627d733a7149f4890d86913d557c85b8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 17:22:49 -0500 Subject: [PATCH 254/508] Take the makefile from revo-next --- Makefile | 27 +++++++++++++++------------ 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/Makefile b/Makefile index 80822ab6f..47b9a0a3c 100644 --- a/Makefile +++ b/Makefile @@ -69,7 +69,7 @@ help: @echo @echo " [Tool Installers]" @echo " qt_sdk_install - Install the QT v4.7.3 tools" - @echo " arm_sdk_install - Install the Code Sourcery ARM gcc toolchain" + @echo " arm_sdk_install - Install the GNU ARM gcc toolchain" @echo " openocd_install - Install the OpenOCD JTAG daemon" @echo " stm32flash_install - Install the stm32flash tool for unbricking boards" @echo " dfuutil_install - Install the dfu-util tool for unbricking F4-based boards" @@ -189,10 +189,10 @@ qt_sdk_clean: $(V1) [ ! -d "$(QT_SDK_DIR)" ] || $(RM) -rf $(QT_SDK_DIR) # Set up ARM (STM32) SDK -ARM_SDK_DIR := $(TOOLS_DIR)/arm-2011.03 +ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_6-2012q1 .PHONY: arm_sdk_install -arm_sdk_install: ARM_SDK_URL := https://sourcery.mentor.com/sgpp/lite/arm/portal/package8736/public/arm-none-eabi/arm-2011.03-42-arm-none-eabi-i686-pc-linux-gnu.tar.bz2 +arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.6/4.6-2012-q1-update/+download/gcc-arm-none-eabi-4_6-2012q1-20120316.tar.bz2 arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) # order-only prereq on directory existance: arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR) @@ -654,7 +654,15 @@ all_$(1)_clean: $$(addsuffix _clean, $$(filter bu_$(1), $$(BU_TARGETS))) all_$(1)_clean: $$(addsuffix _clean, $$(filter ef_$(1), $$(EF_TARGETS))) endef -ALL_BOARDS := coptercontrol pipxtreme revolution simposix +ALL_BOARDS := coptercontrol pipxtreme revolution simposix osd +ALL_BOARDS_BU := coptercontrol pipxtreme simposix + +# SimPosix only builds on Linux so drop it from the list for +# all other platforms. +ifneq ($(UNAME), Linux) +ALL_BOARDS := $(filter-out simposix, $(ALL_BOARDS)) +ALL_BOARDS_BU := $(filter-out simposix, $(ALL_BOARDS_BU)) +endif # SimPosix only builds on Linux so drop it from the list for # all other platforms. @@ -667,6 +675,7 @@ coptercontrol_friendly := CopterControl pipxtreme_friendly := PipXtreme revolution_friendly := Revolution simposix_friendly := SimPosix +osd_friendly := OSD # Short hames of each board (used to display board name in parallel builds) coptercontrol_short := 'cc ' @@ -674,12 +683,6 @@ pipxtreme_short := 'pipx' revolution_short := 'revo' simposix_short := 'posx' osd_short := 'osd ' -# -# SimPosix only builds on Linux so drop it from the list for -# all other platforms. -ifneq ($(UNAME), Linux) -ALL_BOARDS := $(filter-out simposix, $(ALL_BOARDS)) -endif # Short hames of each board (used to display board name in parallel builds) coptercontrol_short := 'cc ' @@ -691,12 +694,12 @@ osd_short := 'osd ' # Start out assuming that we'll build fw, bl and bu for all boards FW_BOARDS := $(ALL_BOARDS) BL_BOARDS := $(ALL_BOARDS) -BU_BOARDS := $(ALL_BOARDS) +BU_BOARDS := $(ALL_BOARDS_BU) EF_BOARDS := $(ALL_BOARDS) # FIXME: The BU image doesn't work for F4 boards so we need to # filter them out to prevent errors. -BU_BOARDS := $(filter-out revolution, $(BU_BOARDS)) +BU_BOARDS := $(filter-out revolution osd, $(BU_BOARDS)) # SimPosix doesn't have a BL, BU or EF target so we need to # filter them out to prevent errors on the all_flight target. From 851923e8b92d25203ffa46233170140183464b2d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 01:35:49 -0500 Subject: [PATCH 255/508] Update the UAVO files --- .../openpilot/uavtalk/uavobjects/Accels.java | 150 ++++++++ .../uavtalk/uavobjects/AltHoldSmoothed.java | 146 ++++++++ .../uavobjects/AltitudeHoldDesired.java | 150 ++++++++ .../uavobjects/AltitudeHoldSettings.java | 169 +++++++++ .../uavtalk/uavobjects/AttitudeSimulated.java | 174 ++++++++++ .../uavtalk/uavobjects/BaroAirspeed.java | 153 ++++++++ .../FixedWingPathFollowerSettings.java | 239 +++++++++++++ .../FixedWingPathFollowerStatus.java | 164 +++++++++ .../uavtalk/uavobjects/GPSSettings.java | 142 ++++++++ .../uavtalk/uavobjects/GPSVelocity.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/Gyros.java | 150 ++++++++ .../uavtalk/uavobjects/GyrosBias.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/MagBias.java | 146 ++++++++ .../uavtalk/uavobjects/Magnetometer.java | 146 ++++++++ .../uavtalk/uavobjects/NEDPosition.java | 146 ++++++++ .../uavtalk/uavobjects/OveroSyncSettings.java | 143 ++++++++ .../uavtalk/uavobjects/OveroSyncStats.java | 165 +++++++++ .../uavtalk/uavobjects/PathDesired.java | 162 +++++++++ .../uavobjects/PathPlannerSettings.java | 151 ++++++++ .../uavtalk/uavobjects/PipXSettings.java | 326 ++++++++++++++++++ .../uavtalk/uavobjects/PipXStatus.java | 301 ++++++++++++++++ .../uavtalk/uavobjects/RevoCalibration.java | 249 +++++++++++++ .../uavtalk/uavobjects/RevoSettings.java | 143 ++++++++ .../uavtalk/uavobjects/TxPIDSettings.java | 225 ++++++++++++ .../uavobjects/VtolPathFollowerSettings.java | 232 +++++++++++++ .../uavtalk/uavobjects/Waypoint.java | 159 +++++++++ .../uavtalk/uavobjects/WaypointActive.java | 138 ++++++++ 27 files changed, 4761 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java new file mode 100644 index 000000000..32437e63e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The accel data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The accel data. + +generated from accels.xml + **/ +public class Accels extends UAVDataObject { + + public Accels() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "m/s^2", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "m/s^2", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "m/s^2", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Accels obj = new Accels(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Accels GetInstance(UAVObjectManager objMngr, int instID) + { + return (Accels)(objMngr.getObject(Accels.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDD9D5FC0; + protected static final String NAME = "Accels"; + protected static String DESCRIPTION = "The accel data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java new file mode 100644 index 000000000..46d03a544 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output on the kalman filter on altitude. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output on the kalman filter on altitude. + +generated from altholdsmoothed.xml + **/ +public class AltHoldSmoothed extends UAVDataObject { + + public AltHoldSmoothed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("0"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List AccelElemNames = new ArrayList(); + AccelElemNames.add("0"); + fields.add( new UAVObjectField("Accel", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltHoldSmoothed obj = new AltHoldSmoothed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltHoldSmoothed GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltHoldSmoothed)(objMngr.getObject(AltHoldSmoothed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2BC6B9D2; + protected static final String NAME = "AltHoldSmoothed"; + protected static String DESCRIPTION = "The output on the kalman filter on altitude."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java new file mode 100644 index 000000000..efe860340 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Holds the desired altitude (from manual control) as well as the desired attitude to pass through + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Holds the desired altitude (from manual control) as well as the desired attitude to pass through + +generated from altitudeholddesired.xml + **/ +public class AltitudeHoldDesired extends UAVDataObject { + + public AltitudeHoldDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldDesired obj = new AltitudeHoldDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldDesired)(objMngr.getObject(AltitudeHoldDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x495BAD6E; + protected static final String NAME = "AltitudeHoldDesired"; + protected static String DESCRIPTION = "Holds the desired altitude (from manual control) as well as the desired attitude to pass through"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java new file mode 100644 index 000000000..77b6774b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AltitudeHold module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AltitudeHold module + +generated from altitudeholdsettings.xml + **/ +public class AltitudeHoldSettings extends UAVDataObject { + + public AltitudeHoldSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List KpElemNames = new ArrayList(); + KpElemNames.add("0"); + fields.add( new UAVObjectField("Kp", "throttle/m", UAVObjectField.FieldType.FLOAT32, KpElemNames, null) ); + + List KiElemNames = new ArrayList(); + KiElemNames.add("0"); + fields.add( new UAVObjectField("Ki", "throttle/m", UAVObjectField.FieldType.FLOAT32, KiElemNames, null) ); + + List KdElemNames = new ArrayList(); + KdElemNames.add("0"); + fields.add( new UAVObjectField("Kd", "throttle/m", UAVObjectField.FieldType.FLOAT32, KdElemNames, null) ); + + List KaElemNames = new ArrayList(); + KaElemNames.add("0"); + fields.add( new UAVObjectField("Ka", "throttle/(m/s^2)", UAVObjectField.FieldType.FLOAT32, KaElemNames, null) ); + + List PressureNoiseElemNames = new ArrayList(); + PressureNoiseElemNames.add("0"); + fields.add( new UAVObjectField("PressureNoise", "m", UAVObjectField.FieldType.FLOAT32, PressureNoiseElemNames, null) ); + + List AccelNoiseElemNames = new ArrayList(); + AccelNoiseElemNames.add("0"); + fields.add( new UAVObjectField("AccelNoise", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelNoiseElemNames, null) ); + + List AccelDriftElemNames = new ArrayList(); + AccelDriftElemNames.add("0"); + fields.add( new UAVObjectField("AccelDrift", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelDriftElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Kp").setValue(0.03); + getField("Ki").setValue(0); + getField("Kd").setValue(0.03); + getField("Ka").setValue(0.005); + getField("PressureNoise").setValue(0.4); + getField("AccelNoise").setValue(5); + getField("AccelDrift").setValue(0.001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldSettings obj = new AltitudeHoldSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldSettings)(objMngr.getObject(AltitudeHoldSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFEC55B42; + protected static final String NAME = "AltitudeHoldSettings"; + protected static String DESCRIPTION = "Settings for the @ref AltitudeHold module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java new file mode 100644 index 000000000..3a713ab04 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java @@ -0,0 +1,174 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The simulated Attitude estimation from @ref Sensors. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The simulated Attitude estimation from @ref Sensors. + +generated from attitudesimulated.xml + **/ +public class AttitudeSimulated extends UAVDataObject { + + public AttitudeSimulated() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSimulated obj = new AttitudeSimulated(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSimulated GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSimulated)(objMngr.getObject(AttitudeSimulated.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9266CE74; + protected static final String NAME = "AttitudeSimulated"; + protected static String DESCRIPTION = "The simulated Attitude estimation from @ref Sensors."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java new file mode 100644 index 000000000..439915741 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java @@ -0,0 +1,153 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + +generated from baroairspeed.xml + **/ +public class BaroAirspeed extends UAVDataObject { + + public BaroAirspeed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirspeedElemNames = new ArrayList(); + AirspeedElemNames.add("0"); + fields.add( new UAVObjectField("Airspeed", "m/s", UAVObjectField.FieldType.FLOAT32, AirspeedElemNames, null) ); + + List SensorValueElemNames = new ArrayList(); + SensorValueElemNames.add("0"); + fields.add( new UAVObjectField("SensorValue", "raw", UAVObjectField.FieldType.UINT16, SensorValueElemNames, null) ); + + List ZeroPointElemNames = new ArrayList(); + ZeroPointElemNames.add("0"); + fields.add( new UAVObjectField("ZeroPoint", "raw", UAVObjectField.FieldType.UINT16, ZeroPointElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAirspeed obj = new BaroAirspeed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAirspeed GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAirspeed)(objMngr.getObject(BaroAirspeed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x169EA4A; + protected static final String NAME = "BaroAirspeed"; + protected static String DESCRIPTION = "The raw data from the dynamic pressure sensor with pressure, temperature and airspeed."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java new file mode 100644 index 000000000..00419bc4c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java @@ -0,0 +1,239 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref FixedWingPathFollowerModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref FixedWingPathFollowerModule + +generated from fixedwingpathfollowersettings.xml + **/ +public class FixedWingPathFollowerSettings extends UAVDataObject { + + public FixedWingPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirSpeedMaxElemNames = new ArrayList(); + AirSpeedMaxElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMax", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMaxElemNames, null) ); + + List AirSpeedMinElemNames = new ArrayList(); + AirSpeedMinElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMin", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMinElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.FLOAT32, VerticalVelMaxElemNames, null) ); + + List HorizontalPosPElemNames = new ArrayList(); + HorizontalPosPElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPElemNames, null) ); + + List VerticalPosPElemNames = new ArrayList(); + VerticalPosPElemNames.add("0"); + fields.add( new UAVObjectField("VerticalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, VerticalPosPElemNames, null) ); + + List CoursePIElemNames = new ArrayList(); + CoursePIElemNames.add("Kp"); + CoursePIElemNames.add("Ki"); + CoursePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("CoursePI", "deg/deg", UAVObjectField.FieldType.FLOAT32, CoursePIElemNames, null) ); + + List SpeedPElemNames = new ArrayList(); + SpeedPElemNames.add("Kp"); + SpeedPElemNames.add("Max"); + fields.add( new UAVObjectField("SpeedP", "(m/s^2) / ((m/s)/(m/s)", UAVObjectField.FieldType.FLOAT32, SpeedPElemNames, null) ); + + List AccelPIElemNames = new ArrayList(); + AccelPIElemNames.add("Kp"); + AccelPIElemNames.add("Ki"); + AccelPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("AccelPI", "deg / (m/s^2)", UAVObjectField.FieldType.FLOAT32, AccelPIElemNames, null) ); + + List VerticalToPitchCrossFeedElemNames = new ArrayList(); + VerticalToPitchCrossFeedElemNames.add("Kp"); + VerticalToPitchCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalToPitchCrossFeed", "deg / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, VerticalToPitchCrossFeedElemNames, null) ); + + List AirspeedToVerticalCrossFeedElemNames = new ArrayList(); + AirspeedToVerticalCrossFeedElemNames.add("Kp"); + AirspeedToVerticalCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("AirspeedToVerticalCrossFeed", "(m/s) / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, AirspeedToVerticalCrossFeedElemNames, null) ); + + List PowerPIElemNames = new ArrayList(); + PowerPIElemNames.add("Kp"); + PowerPIElemNames.add("Ki"); + PowerPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PowerPI", "1/(m/s)", UAVObjectField.FieldType.FLOAT32, PowerPIElemNames, null) ); + + List RollLimitElemNames = new ArrayList(); + RollLimitElemNames.add("Min"); + RollLimitElemNames.add("Neutral"); + RollLimitElemNames.add("Max"); + fields.add( new UAVObjectField("RollLimit", "deg", UAVObjectField.FieldType.FLOAT32, RollLimitElemNames, null) ); + + List PitchLimitElemNames = new ArrayList(); + PitchLimitElemNames.add("Min"); + PitchLimitElemNames.add("Neutral"); + PitchLimitElemNames.add("Max"); + fields.add( new UAVObjectField("PitchLimit", "deg", UAVObjectField.FieldType.FLOAT32, PitchLimitElemNames, null) ); + + List ThrottleLimitElemNames = new ArrayList(); + ThrottleLimitElemNames.add("Min"); + ThrottleLimitElemNames.add("Neutral"); + ThrottleLimitElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleLimit", "", UAVObjectField.FieldType.FLOAT32, ThrottleLimitElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirSpeedMax").setValue(15); + getField("AirSpeedMin").setValue(10); + getField("VerticalVelMax").setValue(10); + getField("HorizontalPosP").setValue(0.05); + getField("VerticalPosP").setValue(0.05); + getField("CoursePI").setValue(0.2,0); + getField("CoursePI").setValue(0,1); + getField("CoursePI").setValue(0,2); + getField("SpeedP").setValue(10,0); + getField("SpeedP").setValue(10,1); + getField("AccelPI").setValue(1.5,0); + getField("AccelPI").setValue(1.5,1); + getField("AccelPI").setValue(20,2); + getField("VerticalToPitchCrossFeed").setValue(50,0); + getField("VerticalToPitchCrossFeed").setValue(5,1); + getField("AirspeedToVerticalCrossFeed").setValue(100,0); + getField("AirspeedToVerticalCrossFeed").setValue(100,1); + getField("PowerPI").setValue(0.01,0); + getField("PowerPI").setValue(0.01,1); + getField("PowerPI").setValue(0.8,2); + getField("RollLimit").setValue(-35,0); + getField("RollLimit").setValue(0,1); + getField("RollLimit").setValue(35,2); + getField("PitchLimit").setValue(-10,0); + getField("PitchLimit").setValue(5,1); + getField("PitchLimit").setValue(20,2); + getField("ThrottleLimit").setValue(0.1,0); + getField("ThrottleLimit").setValue(0.5,1); + getField("ThrottleLimit").setValue(0.9,2); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerSettings obj = new FixedWingPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerSettings)(objMngr.getObject(FixedWingPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8A3F1E02; + protected static final String NAME = "FixedWingPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref FixedWingPathFollowerModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java new file mode 100644 index 000000000..a40be35cf --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Object Storing Debugging Information on PID internals + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Object Storing Debugging Information on PID internals + +generated from fixedwingpathfollowerstatus.xml + **/ +public class FixedWingPathFollowerStatus extends UAVDataObject { + + public FixedWingPathFollowerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List EElemNames = new ArrayList(); + EElemNames.add("Course"); + EElemNames.add("Speed"); + EElemNames.add("Accel"); + EElemNames.add("Power"); + fields.add( new UAVObjectField("E", "", UAVObjectField.FieldType.FLOAT32, EElemNames, null) ); + + List AElemNames = new ArrayList(); + AElemNames.add("Course"); + AElemNames.add("Speed"); + AElemNames.add("Accel"); + AElemNames.add("Power"); + fields.add( new UAVObjectField("A", "", UAVObjectField.FieldType.FLOAT32, AElemNames, null) ); + + List CElemNames = new ArrayList(); + CElemNames.add("Course"); + CElemNames.add("Speed"); + CElemNames.add("Accel"); + CElemNames.add("Power"); + fields.add( new UAVObjectField("C", "", UAVObjectField.FieldType.FLOAT32, CElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("Wind"); + ErrorsElemNames.add("Lowspeed"); + ErrorsElemNames.add("Highspeed"); + ErrorsElemNames.add("Lowpower"); + ErrorsElemNames.add("Highpower"); + ErrorsElemNames.add("Pitchcontrol"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT8, ErrorsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 500; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerStatus obj = new FixedWingPathFollowerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerStatus)(objMngr.getObject(FixedWingPathFollowerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA0D6F6D4; + protected static final String NAME = "FixedWingPathFollowerStatus"; + protected static String DESCRIPTION = "Object Storing Debugging Information on PID internals"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java new file mode 100644 index 000000000..f534fc89c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the GPS + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the GPS + +generated from gpssettings.xml + **/ +public class GPSSettings extends UAVDataObject { + + public GPSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List DataProtocolElemNames = new ArrayList(); + DataProtocolElemNames.add("0"); + List DataProtocolEnumOptions = new ArrayList(); + DataProtocolEnumOptions.add("NMEA"); + DataProtocolEnumOptions.add("UBX"); + fields.add( new UAVObjectField("DataProtocol", "", UAVObjectField.FieldType.ENUM, DataProtocolElemNames, DataProtocolEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("DataProtocol").setValue("NMEA"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSettings obj = new GPSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSettings)(objMngr.getObject(GPSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAC5F6370; + protected static final String NAME = "GPSSettings"; + protected static String DESCRIPTION = "Settings for the GPS"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java new file mode 100644 index 000000000..2ce4a3c62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. + +generated from gpsvelocity.xml + **/ +public class GPSVelocity extends UAVDataObject { + + public GPSVelocity() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSVelocity obj = new GPSVelocity(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSVelocity GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSVelocity)(objMngr.getObject(GPSVelocity.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8245DC80; + protected static final String NAME = "GPSVelocity"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java new file mode 100644 index 000000000..5c960d2e6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyros.xml + **/ +public class Gyros extends UAVDataObject { + + public Gyros() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Gyros obj = new Gyros(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Gyros GetInstance(UAVObjectManager objMngr, int instID) + { + return (Gyros)(objMngr.getObject(Gyros.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4228AF6; + protected static final String NAME = "Gyros"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java new file mode 100644 index 000000000..00bc7da2d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyrosbias.xml + **/ +public class GyrosBias extends UAVDataObject { + + public GyrosBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GyrosBias obj = new GyrosBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GyrosBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (GyrosBias)(objMngr.getObject(GyrosBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE4B6F980; + protected static final String NAME = "GyrosBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java new file mode 100644 index 000000000..398f455d5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from magbias.xml + **/ +public class MagBias extends UAVDataObject { + + public MagBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGau", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGau", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGau", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MagBias obj = new MagBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MagBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (MagBias)(objMngr.getObject(MagBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5043E510; + protected static final String NAME = "MagBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java new file mode 100644 index 000000000..583817cca --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The mag data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The mag data. + +generated from magnetometer.xml + **/ +public class Magnetometer extends UAVDataObject { + + public Magnetometer() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGa", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGa", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGa", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Magnetometer obj = new Magnetometer(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Magnetometer GetInstance(UAVObjectManager objMngr, int instID) + { + return (Magnetometer)(objMngr.getObject(Magnetometer.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x813B55DE; + protected static final String NAME = "Magnetometer"; + protected static String DESCRIPTION = "The mag data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java new file mode 100644 index 000000000..0aa67862e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from nedposition.xml + **/ +public class NEDPosition extends UAVDataObject { + + public NEDPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NEDPosition obj = new NEDPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NEDPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (NEDPosition)(objMngr.getObject(NEDPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FB15A00; + protected static final String NAME = "NEDPosition"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java new file mode 100644 index 000000000..c680d230c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to control the behavior of the overo sync module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to control the behavior of the overo sync module + +generated from overosyncsettings.xml + **/ +public class OveroSyncSettings extends UAVDataObject { + + public OveroSyncSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List LogOnElemNames = new ArrayList(); + LogOnElemNames.add("0"); + List LogOnEnumOptions = new ArrayList(); + LogOnEnumOptions.add("Never"); + LogOnEnumOptions.add("Always"); + LogOnEnumOptions.add("Armed"); + fields.add( new UAVObjectField("LogOn", "", UAVObjectField.FieldType.ENUM, LogOnElemNames, LogOnEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("LogOn").setValue("Armed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncSettings obj = new OveroSyncSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncSettings)(objMngr.getObject(OveroSyncSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA1ABC278; + protected static final String NAME = "OveroSyncSettings"; + protected static String DESCRIPTION = "Settings to control the behavior of the overo sync module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java new file mode 100644 index 000000000..4c31f21dd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains statistics on transfer rate to and from over + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains statistics on transfer rate to and from over + +generated from overosyncstats.xml + **/ +public class OveroSyncStats extends UAVDataObject { + + public OveroSyncStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SendElemNames = new ArrayList(); + SendElemNames.add("0"); + fields.add( new UAVObjectField("Send", "B/s", UAVObjectField.FieldType.UINT32, SendElemNames, null) ); + + List ReceivedElemNames = new ArrayList(); + ReceivedElemNames.add("0"); + fields.add( new UAVObjectField("Received", "B/s", UAVObjectField.FieldType.UINT32, ReceivedElemNames, null) ); + + List FramesyncErrorsElemNames = new ArrayList(); + FramesyncErrorsElemNames.add("0"); + fields.add( new UAVObjectField("FramesyncErrors", "count", UAVObjectField.FieldType.UINT32, FramesyncErrorsElemNames, null) ); + + List UnderrunErrorsElemNames = new ArrayList(); + UnderrunErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UnderrunErrors", "count", UAVObjectField.FieldType.UINT32, UnderrunErrorsElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "", UAVObjectField.FieldType.UINT32, DroppedUpdatesElemNames, null) ); + + List PacketsElemNames = new ArrayList(); + PacketsElemNames.add("0"); + fields.add( new UAVObjectField("Packets", "", UAVObjectField.FieldType.UINT32, PacketsElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncStats obj = new OveroSyncStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncStats)(objMngr.getObject(OveroSyncStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD2085FAC; + protected static final String NAME = "OveroSyncStats"; + protected static String DESCRIPTION = "Maintains statistics on transfer rate to and from over"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java new file mode 100644 index 000000000..38e710477 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + +generated from pathdesired.xml + **/ +public class PathDesired extends UAVDataObject { + + public PathDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StartElemNames = new ArrayList(); + StartElemNames.add("North"); + StartElemNames.add("East"); + StartElemNames.add("Down"); + fields.add( new UAVObjectField("Start", "m", UAVObjectField.FieldType.FLOAT32, StartElemNames, null) ); + + List EndElemNames = new ArrayList(); + EndElemNames.add("North"); + EndElemNames.add("East"); + EndElemNames.add("Down"); + fields.add( new UAVObjectField("End", "m", UAVObjectField.FieldType.FLOAT32, EndElemNames, null) ); + + List StartingVelocityElemNames = new ArrayList(); + StartingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("StartingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, StartingVelocityElemNames, null) ); + + List EndingVelocityElemNames = new ArrayList(); + EndingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("EndingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, EndingVelocityElemNames, null) ); + + List ModeElemNames = new ArrayList(); + ModeElemNames.add("0"); + List ModeEnumOptions = new ArrayList(); + ModeEnumOptions.add("Endpoint"); + ModeEnumOptions.add("Path"); + ModeEnumOptions.add("Land"); + fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathDesired obj = new PathDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathDesired)(objMngr.getObject(PathDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5A4DC71A; + protected static final String NAME = "PathDesired"; + protected static String DESCRIPTION = "The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java new file mode 100644 index 000000000..fb6b66e19 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref PathPlanner Module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref PathPlanner Module + +generated from pathplannersettings.xml + **/ +public class PathPlannerSettings extends UAVDataObject { + + public PathPlannerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PathModeElemNames = new ArrayList(); + PathModeElemNames.add("0"); + List PathModeEnumOptions = new ArrayList(); + PathModeEnumOptions.add("ENDPOINT"); + PathModeEnumOptions.add("PATH"); + fields.add( new UAVObjectField("PathMode", "", UAVObjectField.FieldType.ENUM, PathModeElemNames, PathModeEnumOptions) ); + + List PreprogrammedPathElemNames = new ArrayList(); + PreprogrammedPathElemNames.add("0"); + List PreprogrammedPathEnumOptions = new ArrayList(); + PreprogrammedPathEnumOptions.add("NONE"); + PreprogrammedPathEnumOptions.add("10M_BOX"); + PreprogrammedPathEnumOptions.add("LOGO"); + fields.add( new UAVObjectField("PreprogrammedPath", "", UAVObjectField.FieldType.ENUM, PreprogrammedPathElemNames, PreprogrammedPathEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PathMode").setValue("PATH"); + getField("PreprogrammedPath").setValue("NONE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathPlannerSettings obj = new PathPlannerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathPlannerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathPlannerSettings)(objMngr.getObject(PathPlannerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x290E45DA; + protected static final String NAME = "PathPlannerSettings"; + protected static String DESCRIPTION = "Settings for the @ref PathPlanner Module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java new file mode 100644 index 000000000..aa5387148 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java @@ -0,0 +1,326 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme configurations options. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme configurations options. + +generated from pipxsettings.xml + **/ +public class PipXSettings extends UAVDataObject { + + public PipXSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PairIDElemNames = new ArrayList(); + PairIDElemNames.add("0"); + fields.add( new UAVObjectField("PairID", "", UAVObjectField.FieldType.UINT32, PairIDElemNames, null) ); + + List FrequencyElemNames = new ArrayList(); + FrequencyElemNames.add("0"); + fields.add( new UAVObjectField("Frequency", "", UAVObjectField.FieldType.UINT32, FrequencyElemNames, null) ); + + List SendTimeoutElemNames = new ArrayList(); + SendTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("SendTimeout", "ms", UAVObjectField.FieldType.UINT16, SendTimeoutElemNames, null) ); + + List TelemetryConfigElemNames = new ArrayList(); + TelemetryConfigElemNames.add("0"); + List TelemetryConfigEnumOptions = new ArrayList(); + TelemetryConfigEnumOptions.add("Disabled"); + TelemetryConfigEnumOptions.add("Serial"); + TelemetryConfigEnumOptions.add("UAVTalk"); + TelemetryConfigEnumOptions.add("GCS"); + TelemetryConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("TelemetryConfig", "function", UAVObjectField.FieldType.ENUM, TelemetryConfigElemNames, TelemetryConfigEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List FlexiConfigElemNames = new ArrayList(); + FlexiConfigElemNames.add("0"); + List FlexiConfigEnumOptions = new ArrayList(); + FlexiConfigEnumOptions.add("Disabled"); + FlexiConfigEnumOptions.add("Serial"); + FlexiConfigEnumOptions.add("UAVTalk"); + FlexiConfigEnumOptions.add("GCS"); + FlexiConfigEnumOptions.add("PPM_In"); + FlexiConfigEnumOptions.add("PPM_Out"); + FlexiConfigEnumOptions.add("RSSI"); + FlexiConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("FlexiConfig", "function", UAVObjectField.FieldType.ENUM, FlexiConfigElemNames, FlexiConfigEnumOptions) ); + + List FlexiSpeedElemNames = new ArrayList(); + FlexiSpeedElemNames.add("0"); + List FlexiSpeedEnumOptions = new ArrayList(); + FlexiSpeedEnumOptions.add("2400"); + FlexiSpeedEnumOptions.add("4800"); + FlexiSpeedEnumOptions.add("9600"); + FlexiSpeedEnumOptions.add("19200"); + FlexiSpeedEnumOptions.add("38400"); + FlexiSpeedEnumOptions.add("57600"); + FlexiSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("FlexiSpeed", "bps", UAVObjectField.FieldType.ENUM, FlexiSpeedElemNames, FlexiSpeedEnumOptions) ); + + List VCPConfigElemNames = new ArrayList(); + VCPConfigElemNames.add("0"); + List VCPConfigEnumOptions = new ArrayList(); + VCPConfigEnumOptions.add("Disabled"); + VCPConfigEnumOptions.add("Serial"); + VCPConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("VCPConfig", "function", UAVObjectField.FieldType.ENUM, VCPConfigElemNames, VCPConfigEnumOptions) ); + + List VCPSpeedElemNames = new ArrayList(); + VCPSpeedElemNames.add("0"); + List VCPSpeedEnumOptions = new ArrayList(); + VCPSpeedEnumOptions.add("2400"); + VCPSpeedEnumOptions.add("4800"); + VCPSpeedEnumOptions.add("9600"); + VCPSpeedEnumOptions.add("19200"); + VCPSpeedEnumOptions.add("38400"); + VCPSpeedEnumOptions.add("57600"); + VCPSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("VCPSpeed", "bps", UAVObjectField.FieldType.ENUM, VCPSpeedElemNames, VCPSpeedEnumOptions) ); + + List RFSpeedElemNames = new ArrayList(); + RFSpeedElemNames.add("0"); + List RFSpeedEnumOptions = new ArrayList(); + RFSpeedEnumOptions.add("2400"); + RFSpeedEnumOptions.add("4800"); + RFSpeedEnumOptions.add("9600"); + RFSpeedEnumOptions.add("19200"); + RFSpeedEnumOptions.add("38400"); + RFSpeedEnumOptions.add("57600"); + RFSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("RFSpeed", "bps", UAVObjectField.FieldType.ENUM, RFSpeedElemNames, RFSpeedEnumOptions) ); + + List MaxRFPowerElemNames = new ArrayList(); + MaxRFPowerElemNames.add("0"); + List MaxRFPowerEnumOptions = new ArrayList(); + MaxRFPowerEnumOptions.add("1.25"); + MaxRFPowerEnumOptions.add("1.6"); + MaxRFPowerEnumOptions.add("3.16"); + MaxRFPowerEnumOptions.add("6.3"); + MaxRFPowerEnumOptions.add("12.6"); + MaxRFPowerEnumOptions.add("25"); + MaxRFPowerEnumOptions.add("50"); + MaxRFPowerEnumOptions.add("100"); + fields.add( new UAVObjectField("MaxRFPower", "mW", UAVObjectField.FieldType.ENUM, MaxRFPowerElemNames, MaxRFPowerEnumOptions) ); + + List MinPacketSizeElemNames = new ArrayList(); + MinPacketSizeElemNames.add("0"); + fields.add( new UAVObjectField("MinPacketSize", "bytes", UAVObjectField.FieldType.UINT8, MinPacketSizeElemNames, null) ); + + List FrequencyCalibrationElemNames = new ArrayList(); + FrequencyCalibrationElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyCalibration", "", UAVObjectField.FieldType.UINT8, FrequencyCalibrationElemNames, null) ); + + List AESKeyElemNames = new ArrayList(); + AESKeyElemNames.add("0"); + AESKeyElemNames.add("1"); + AESKeyElemNames.add("2"); + AESKeyElemNames.add("3"); + AESKeyElemNames.add("4"); + AESKeyElemNames.add("5"); + AESKeyElemNames.add("6"); + AESKeyElemNames.add("7"); + AESKeyElemNames.add("8"); + AESKeyElemNames.add("9"); + AESKeyElemNames.add("10"); + AESKeyElemNames.add("11"); + AESKeyElemNames.add("12"); + AESKeyElemNames.add("13"); + AESKeyElemNames.add("14"); + AESKeyElemNames.add("15"); + AESKeyElemNames.add("16"); + AESKeyElemNames.add("17"); + AESKeyElemNames.add("18"); + AESKeyElemNames.add("19"); + AESKeyElemNames.add("20"); + AESKeyElemNames.add("21"); + AESKeyElemNames.add("22"); + AESKeyElemNames.add("23"); + AESKeyElemNames.add("24"); + AESKeyElemNames.add("25"); + AESKeyElemNames.add("26"); + AESKeyElemNames.add("27"); + AESKeyElemNames.add("28"); + AESKeyElemNames.add("29"); + AESKeyElemNames.add("30"); + AESKeyElemNames.add("31"); + fields.add( new UAVObjectField("AESKey", "", UAVObjectField.FieldType.UINT8, AESKeyElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PairID").setValue(0); + getField("Frequency").setValue(434000000); + getField("SendTimeout").setValue(50); + getField("TelemetryConfig").setValue("UAVTalk"); + getField("TelemetrySpeed").setValue("57600"); + getField("FlexiConfig").setValue("Disabled"); + getField("FlexiSpeed").setValue("57600"); + getField("VCPConfig").setValue("Disabled"); + getField("VCPSpeed").setValue("57600"); + getField("RFSpeed").setValue("115200"); + getField("MaxRFPower").setValue("100"); + getField("MinPacketSize").setValue(50); + getField("FrequencyCalibration").setValue(127); + getField("AESKey").setValue(0,0); + getField("AESKey").setValue(0,1); + getField("AESKey").setValue(0,2); + getField("AESKey").setValue(0,3); + getField("AESKey").setValue(0,4); + getField("AESKey").setValue(0,5); + getField("AESKey").setValue(0,6); + getField("AESKey").setValue(0,7); + getField("AESKey").setValue(0,8); + getField("AESKey").setValue(0,9); + getField("AESKey").setValue(0,10); + getField("AESKey").setValue(0,11); + getField("AESKey").setValue(0,12); + getField("AESKey").setValue(0,13); + getField("AESKey").setValue(0,14); + getField("AESKey").setValue(0,15); + getField("AESKey").setValue(0,16); + getField("AESKey").setValue(0,17); + getField("AESKey").setValue(0,18); + getField("AESKey").setValue(0,19); + getField("AESKey").setValue(0,20); + getField("AESKey").setValue(0,21); + getField("AESKey").setValue(0,22); + getField("AESKey").setValue(0,23); + getField("AESKey").setValue(0,24); + getField("AESKey").setValue(0,25); + getField("AESKey").setValue(0,26); + getField("AESKey").setValue(0,27); + getField("AESKey").setValue(0,28); + getField("AESKey").setValue(0,29); + getField("AESKey").setValue(0,30); + getField("AESKey").setValue(0,31); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXSettings obj = new PipXSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXSettings)(objMngr.getObject(PipXSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA192BCA; + protected static final String NAME = "PipXSettings"; + protected static String DESCRIPTION = "PipXtreme configurations options."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java new file mode 100644 index 000000000..fb6a91e33 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java @@ -0,0 +1,301 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme device status. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme device status. + +generated from pipxstatus.xml + **/ +public class PipXStatus extends UAVDataObject { + + public PipXStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MinFrequencyElemNames = new ArrayList(); + MinFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MinFrequency", "Hz", UAVObjectField.FieldType.UINT32, MinFrequencyElemNames, null) ); + + List MaxFrequencyElemNames = new ArrayList(); + MaxFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MaxFrequency", "Hz", UAVObjectField.FieldType.UINT32, MaxFrequencyElemNames, null) ); + + List FrequencyStepSizeElemNames = new ArrayList(); + FrequencyStepSizeElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyStepSize", "", UAVObjectField.FieldType.FLOAT32, FrequencyStepSizeElemNames, null) ); + + List DeviceIDElemNames = new ArrayList(); + DeviceIDElemNames.add("0"); + fields.add( new UAVObjectField("DeviceID", "", UAVObjectField.FieldType.UINT32, DeviceIDElemNames, null) ); + + List AFCElemNames = new ArrayList(); + AFCElemNames.add("0"); + fields.add( new UAVObjectField("AFC", "", UAVObjectField.FieldType.INT32, AFCElemNames, null) ); + + List PairIDsElemNames = new ArrayList(); + PairIDsElemNames.add("0"); + PairIDsElemNames.add("1"); + PairIDsElemNames.add("2"); + PairIDsElemNames.add("3"); + fields.add( new UAVObjectField("PairIDs", "", UAVObjectField.FieldType.UINT32, PairIDsElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List RetriesElemNames = new ArrayList(); + RetriesElemNames.add("0"); + fields.add( new UAVObjectField("Retries", "", UAVObjectField.FieldType.UINT16, RetriesElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("0"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT16, ErrorsElemNames, null) ); + + List UAVTalkErrorsElemNames = new ArrayList(); + UAVTalkErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UAVTalkErrors", "", UAVObjectField.FieldType.UINT16, UAVTalkErrorsElemNames, null) ); + + List DroppedElemNames = new ArrayList(); + DroppedElemNames.add("0"); + fields.add( new UAVObjectField("Dropped", "", UAVObjectField.FieldType.UINT16, DroppedElemNames, null) ); + + List ResetsElemNames = new ArrayList(); + ResetsElemNames.add("0"); + fields.add( new UAVObjectField("Resets", "", UAVObjectField.FieldType.UINT16, ResetsElemNames, null) ); + + List TXRateElemNames = new ArrayList(); + TXRateElemNames.add("0"); + fields.add( new UAVObjectField("TXRate", "Bps", UAVObjectField.FieldType.UINT16, TXRateElemNames, null) ); + + List RXRateElemNames = new ArrayList(); + RXRateElemNames.add("0"); + fields.add( new UAVObjectField("RXRate", "Bps", UAVObjectField.FieldType.UINT16, RXRateElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List FrequencyBandElemNames = new ArrayList(); + FrequencyBandElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyBand", "", UAVObjectField.FieldType.UINT8, FrequencyBandElemNames, null) ); + + List RSSIElemNames = new ArrayList(); + RSSIElemNames.add("0"); + fields.add( new UAVObjectField("RSSI", "dBm", UAVObjectField.FieldType.INT8, RSSIElemNames, null) ); + + List LinkStateElemNames = new ArrayList(); + LinkStateElemNames.add("0"); + List LinkStateEnumOptions = new ArrayList(); + LinkStateEnumOptions.add("Disconnected"); + LinkStateEnumOptions.add("Connecting"); + LinkStateEnumOptions.add("Connected"); + fields.add( new UAVObjectField("LinkState", "function", UAVObjectField.FieldType.ENUM, LinkStateElemNames, LinkStateEnumOptions) ); + + List PairSignalStrengthsElemNames = new ArrayList(); + PairSignalStrengthsElemNames.add("0"); + PairSignalStrengthsElemNames.add("1"); + PairSignalStrengthsElemNames.add("2"); + PairSignalStrengthsElemNames.add("3"); + fields.add( new UAVObjectField("PairSignalStrengths", "dBm", UAVObjectField.FieldType.INT8, PairSignalStrengthsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MinFrequency").setValue(0); + getField("MaxFrequency").setValue(0); + getField("FrequencyStepSize").setValue(0); + getField("DeviceID").setValue(0); + getField("AFC").setValue(0); + getField("PairIDs").setValue(0,0); + getField("PairIDs").setValue(0,1); + getField("PairIDs").setValue(0,2); + getField("PairIDs").setValue(0,3); + getField("Retries").setValue(0); + getField("Errors").setValue(0); + getField("UAVTalkErrors").setValue(0); + getField("Dropped").setValue(0); + getField("Resets").setValue(0); + getField("TXRate").setValue(0); + getField("RXRate").setValue(0); + getField("FrequencyBand").setValue(0); + getField("RSSI").setValue(0); + getField("LinkState").setValue("Disconnected"); + getField("PairSignalStrengths").setValue(-127,0); + getField("PairSignalStrengths").setValue(-127,1); + getField("PairSignalStrengths").setValue(-127,2); + getField("PairSignalStrengths").setValue(-127,3); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXStatus obj = new PipXStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXStatus)(objMngr.getObject(PipXStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3FC68A86; + protected static final String NAME = "PipXStatus"; + protected static String DESCRIPTION = "PipXtreme device status."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java new file mode 100644 index 000000000..940f78875 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java @@ -0,0 +1,249 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the INS to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the INS to control the algorithm and what is updated + +generated from revocalibration.xml + **/ +public class RevoCalibration extends UAVDataObject { + + public RevoCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "gain", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "deg/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "gain", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(deg/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcoeffElemNames = new ArrayList(); + gyro_tempcoeffElemNames.add("X"); + gyro_tempcoeffElemNames.add("Y"); + gyro_tempcoeffElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcoeff", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, gyro_tempcoeffElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "gain", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List gps_varElemNames = new ArrayList(); + gps_varElemNames.add("Pos"); + gps_varElemNames.add("Vel"); + fields.add( new UAVObjectField("gps_var", "m^2", UAVObjectField.FieldType.FLOAT32, gps_varElemNames, null) ); + + List baro_varElemNames = new ArrayList(); + baro_varElemNames.add("0"); + fields.add( new UAVObjectField("baro_var", "m^2", UAVObjectField.FieldType.FLOAT32, baro_varElemNames, null) ); + + List MagBiasNullingRateElemNames = new ArrayList(); + MagBiasNullingRateElemNames.add("0"); + fields.add( new UAVObjectField("MagBiasNullingRate", "", UAVObjectField.FieldType.FLOAT32, MagBiasNullingRateElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("FALSE"); + BiasCorrectedRawEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("accel_bias").setValue(0,0); + getField("accel_bias").setValue(0,1); + getField("accel_bias").setValue(0,2); + getField("accel_scale").setValue(1,0); + getField("accel_scale").setValue(1,1); + getField("accel_scale").setValue(1,2); + getField("accel_var").setValue(0.01,0); + getField("accel_var").setValue(0.01,1); + getField("accel_var").setValue(0.01,2); + getField("gyro_bias").setValue(0,0); + getField("gyro_bias").setValue(0,1); + getField("gyro_bias").setValue(0,2); + getField("gyro_scale").setValue(1,0); + getField("gyro_scale").setValue(1,1); + getField("gyro_scale").setValue(1,2); + getField("gyro_var").setValue(0.01,0); + getField("gyro_var").setValue(0.01,1); + getField("gyro_var").setValue(0.01,2); + getField("gyro_tempcoeff").setValue(1,0); + getField("gyro_tempcoeff").setValue(1,1); + getField("gyro_tempcoeff").setValue(1,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); + getField("mag_var").setValue(0.01,0); + getField("mag_var").setValue(0.01,1); + getField("mag_var").setValue(10,2); + getField("gps_var").setValue(1,0); + getField("gps_var").setValue(1,1); + getField("baro_var").setValue(1); + getField("MagBiasNullingRate").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoCalibration obj = new RevoCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoCalibration)(objMngr.getObject(RevoCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA2A63C7C; + protected static final String NAME = "RevoCalibration"; + protected static String DESCRIPTION = "Settings for the INS to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java new file mode 100644 index 000000000..5e36565b2 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the revo to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the revo to control the algorithm and what is updated + +generated from revosettings.xml + **/ +public class RevoSettings extends UAVDataObject { + + public RevoSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FusionAlgorithmElemNames = new ArrayList(); + FusionAlgorithmElemNames.add("0"); + List FusionAlgorithmEnumOptions = new ArrayList(); + FusionAlgorithmEnumOptions.add("Complimentary"); + FusionAlgorithmEnumOptions.add("INSIndoor"); + FusionAlgorithmEnumOptions.add("INSOutdoor"); + fields.add( new UAVObjectField("FusionAlgorithm", "", UAVObjectField.FieldType.ENUM, FusionAlgorithmElemNames, FusionAlgorithmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FusionAlgorithm").setValue("Complimentary"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoSettings obj = new RevoSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoSettings)(objMngr.getObject(RevoSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2DA70EA; + protected static final String NAME = "RevoSettings"; + protected static String DESCRIPTION = "Settings for the revo to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java new file mode 100644 index 000000000..789f31b3f --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + +generated from txpidsettings.xml + **/ +public class TxPIDSettings extends UAVDataObject { + + public TxPIDSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ThrottleRangeElemNames = new ArrayList(); + ThrottleRangeElemNames.add("Min"); + ThrottleRangeElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleRange", "%", UAVObjectField.FieldType.FLOAT32, ThrottleRangeElemNames, null) ); + + List MinPIDElemNames = new ArrayList(); + MinPIDElemNames.add("Instance1"); + MinPIDElemNames.add("Instance2"); + MinPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MinPID", "", UAVObjectField.FieldType.FLOAT32, MinPIDElemNames, null) ); + + List MaxPIDElemNames = new ArrayList(); + MaxPIDElemNames.add("Instance1"); + MaxPIDElemNames.add("Instance2"); + MaxPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MaxPID", "", UAVObjectField.FieldType.FLOAT32, MaxPIDElemNames, null) ); + + List UpdateModeElemNames = new ArrayList(); + UpdateModeElemNames.add("0"); + List UpdateModeEnumOptions = new ArrayList(); + UpdateModeEnumOptions.add("Never"); + UpdateModeEnumOptions.add("When Armed"); + UpdateModeEnumOptions.add("Always"); + fields.add( new UAVObjectField("UpdateMode", "option", UAVObjectField.FieldType.ENUM, UpdateModeElemNames, UpdateModeEnumOptions) ); + + List InputsElemNames = new ArrayList(); + InputsElemNames.add("Instance1"); + InputsElemNames.add("Instance2"); + InputsElemNames.add("Instance3"); + List InputsEnumOptions = new ArrayList(); + InputsEnumOptions.add("Throttle"); + InputsEnumOptions.add("Accessory0"); + InputsEnumOptions.add("Accessory1"); + InputsEnumOptions.add("Accessory2"); + InputsEnumOptions.add("Accessory3"); + InputsEnumOptions.add("Accessory4"); + InputsEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Inputs", "channel", UAVObjectField.FieldType.ENUM, InputsElemNames, InputsEnumOptions) ); + + List PIDsElemNames = new ArrayList(); + PIDsElemNames.add("Instance1"); + PIDsElemNames.add("Instance2"); + PIDsElemNames.add("Instance3"); + List PIDsEnumOptions = new ArrayList(); + PIDsEnumOptions.add("Disabled"); + PIDsEnumOptions.add("Roll Rate.Kp"); + PIDsEnumOptions.add("Pitch Rate.Kp"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kp"); + PIDsEnumOptions.add("Yaw Rate.Kp"); + PIDsEnumOptions.add("Roll Rate.Ki"); + PIDsEnumOptions.add("Pitch Rate.Ki"); + PIDsEnumOptions.add("Roll+Pitch Rate.Ki"); + PIDsEnumOptions.add("Yaw Rate.Ki"); + PIDsEnumOptions.add("Roll Rate.Kd"); + PIDsEnumOptions.add("Pitch Rate.Kd"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kd"); + PIDsEnumOptions.add("Yaw Rate.Kd"); + PIDsEnumOptions.add("Roll Rate.ILimit"); + PIDsEnumOptions.add("Pitch Rate.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Rate.ILimit"); + PIDsEnumOptions.add("Yaw Rate.ILimit"); + PIDsEnumOptions.add("Roll Attitude.Kp"); + PIDsEnumOptions.add("Pitch Attitude.Kp"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Kp"); + PIDsEnumOptions.add("Yaw Attitude.Kp"); + PIDsEnumOptions.add("Roll Attitude.Ki"); + PIDsEnumOptions.add("Pitch Attitude.Ki"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Ki"); + PIDsEnumOptions.add("Yaw Attitude.Ki"); + PIDsEnumOptions.add("Roll Attitude.ILimit"); + PIDsEnumOptions.add("Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Yaw Attitude.ILimit"); + PIDsEnumOptions.add("GyroTau"); + fields.add( new UAVObjectField("PIDs", "option", UAVObjectField.FieldType.ENUM, PIDsElemNames, PIDsEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("ThrottleRange").setValue(0.2,0); + getField("ThrottleRange").setValue(0.8,1); + getField("MinPID").setValue(0,0); + getField("MinPID").setValue(0,1); + getField("MinPID").setValue(0,2); + getField("MaxPID").setValue(0,0); + getField("MaxPID").setValue(0,1); + getField("MaxPID").setValue(0,2); + getField("UpdateMode").setValue("When Armed"); + getField("Inputs").setValue("Throttle",0); + getField("Inputs").setValue("Accessory0",1); + getField("Inputs").setValue("Accessory1",2); + getField("PIDs").setValue("Disabled",0); + getField("PIDs").setValue("Disabled",1); + getField("PIDs").setValue("Disabled",2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TxPIDSettings obj = new TxPIDSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TxPIDSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TxPIDSettings)(objMngr.getObject(TxPIDSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x42B2D2AE; + protected static final String NAME = "TxPIDSettings"; + protected static String DESCRIPTION = "Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java new file mode 100644 index 000000000..b3c01dc8a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java @@ -0,0 +1,232 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref VtolPathFollower module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref VtolPathFollower module + +generated from vtolpathfollowersettings.xml + **/ +public class VtolPathFollowerSettings extends UAVDataObject { + + public VtolPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List VelocityFeedforwardElemNames = new ArrayList(); + VelocityFeedforwardElemNames.add("0"); + fields.add( new UAVObjectField("VelocityFeedforward", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, VelocityFeedforwardElemNames, null) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List VelocitySourceElemNames = new ArrayList(); + VelocitySourceElemNames.add("0"); + List VelocitySourceEnumOptions = new ArrayList(); + VelocitySourceEnumOptions.add("EKF"); + VelocitySourceEnumOptions.add("NEDVEL"); + VelocitySourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("VelocitySource", "", UAVObjectField.FieldType.ENUM, VelocitySourceElemNames, VelocitySourceEnumOptions) ); + + List PositionSourceElemNames = new ArrayList(); + PositionSourceElemNames.add("0"); + List PositionSourceEnumOptions = new ArrayList(); + PositionSourceEnumOptions.add("EKF"); + PositionSourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("PositionSource", "", UAVObjectField.FieldType.ENUM, PositionSourceElemNames, PositionSourceEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("HorizontalPosPI").setValue(1,0); + getField("HorizontalPosPI").setValue(0,1); + getField("HorizontalPosPI").setValue(0,2); + getField("HorizontalVelPID").setValue(5,0); + getField("HorizontalVelPID").setValue(0,1); + getField("HorizontalVelPID").setValue(1,2); + getField("HorizontalVelPID").setValue(0,3); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("VelocityFeedforward").setValue(0); + getField("MaxRollPitch").setValue(20); + getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(10); + getField("VerticalVelMax").setValue(1); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); + getField("VelocitySource").setValue("EKF"); + getField("PositionSource").setValue("EKF"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VtolPathFollowerSettings obj = new VtolPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VtolPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (VtolPathFollowerSettings)(objMngr.getObject(VtolPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x973991F6; + protected static final String NAME = "VtolPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref VtolPathFollower module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java new file mode 100644 index 000000000..4db7179ad --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + +generated from waypoint.xml + **/ +public class Waypoint extends UAVDataObject { + + public Waypoint() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List YawDesiredElemNames = new ArrayList(); + YawDesiredElemNames.add("0"); + fields.add( new UAVObjectField("YawDesired", "deg", UAVObjectField.FieldType.FLOAT32, YawDesiredElemNames, null) ); + + List ActionElemNames = new ArrayList(); + ActionElemNames.add("0"); + List ActionEnumOptions = new ArrayList(); + ActionEnumOptions.add("PathToNext"); + ActionEnumOptions.add("EndpointToNext"); + ActionEnumOptions.add("Land"); + ActionEnumOptions.add("Stop"); + fields.add( new UAVObjectField("Action", "", UAVObjectField.FieldType.ENUM, ActionElemNames, ActionEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 4000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Waypoint obj = new Waypoint(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Waypoint GetInstance(UAVObjectManager objMngr, int instID) + { + return (Waypoint)(objMngr.getObject(Waypoint.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x338C5F90; + protected static final String NAME = "Waypoint"; + protected static String DESCRIPTION = "A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module"; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java new file mode 100644 index 000000000..06f3ab6c4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java @@ -0,0 +1,138 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Indicates the currently active waypoint + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Indicates the currently active waypoint + +generated from waypointactive.xml + **/ +public class WaypointActive extends UAVDataObject { + + public WaypointActive() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List IndexElemNames = new ArrayList(); + IndexElemNames.add("0"); + fields.add( new UAVObjectField("Index", "", UAVObjectField.FieldType.UINT8, IndexElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WaypointActive obj = new WaypointActive(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WaypointActive GetInstance(UAVObjectManager objMngr, int instID) + { + return (WaypointActive)(objMngr.getObject(WaypointActive.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1EA5B192; + protected static final String NAME = "WaypointActive"; + protected static String DESCRIPTION = "Indicates the currently active waypoint"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From 2881a4573fd514b54c7bd31befbba7f8ea2917d1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 02:14:12 -0500 Subject: [PATCH 256/508] Allow selecting the IP address from the preferences --- androidgcs/res/xml/preferences.xml | 2 +- .../src/org/openpilot/androidgcs/TcpUAVTalk.java | 13 +++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 24fd43b5e..285e7b6d7 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -10,6 +10,6 @@ + android:key="ip_address" />
diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index 47074f968..f5d40040b 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -8,6 +8,8 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import android.content.Context; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; public class TcpUAVTalk { @@ -17,14 +19,17 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "10.21.18.120"; + private String ip_address = "1"; public final static int PORT = 9001; private UAVTalk uavTalk; private boolean connected; public TcpUAVTalk(Context caller) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + ip_address = prefs.getString("ip_address","127.0.0.1"); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -47,11 +52,11 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); InetAddress serverAddr = null; try { - serverAddr = InetAddress.getByName(IP_ADDRESS); + serverAddr = InetAddress.getByName(ip_address); } catch (UnknownHostException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From c6073772fb2f5506977e6a121f31f807e47227b0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 03:18:26 -0500 Subject: [PATCH 257/508] Make port and bluetooth adapter be listed in the preferences. Using the BT adapter not working yet. --- androidgcs/res/xml/preferences.xml | 8 ++++++++ .../openpilot/androidgcs/BluetoothUAVTalk.java | 17 ++++++++++++----- .../androidgcs/OPTelemetryService.java | 2 +- .../org/openpilot/androidgcs/TcpUAVTalk.java | 12 ++++++++---- 4 files changed, 29 insertions(+), 10 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 285e7b6d7..3a9103b49 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -11,5 +11,13 @@ android:summary="Enter a TCP/IP address here" android:defaultValue="192.168.0.1" android:title="IP address:" android:key="ip_address" /> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java index b240f3adc..c00db0bea 100644 --- a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -7,6 +7,7 @@ import java.util.UUID; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; +import android.annotation.TargetApi; import android.app.Activity; import android.bluetooth.BluetoothAdapter; import android.bluetooth.BluetoothDevice; @@ -14,16 +15,18 @@ import android.bluetooth.BluetoothSocket; import android.content.BroadcastReceiver; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; -public class BluetoothUAVTalk { +@TargetApi(10) public class BluetoothUAVTalk { private final String TAG = "BluetoothUAVTalk"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String DEVICE_NAME = "RN42-222D"; + private String device_name = "RN42-222D"; private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); private BluetoothAdapter mBluetoothAdapter; @@ -32,8 +35,12 @@ public class BluetoothUAVTalk { private UAVTalk uavTalk; private boolean connected; - public BluetoothUAVTalk(Context caller, String deviceName) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + public BluetoothUAVTalk(Context caller) { + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + device_name = prefs.getString("bluetooth_mac",""); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + device_name); connected = false; device = null; @@ -93,7 +100,7 @@ public class BluetoothUAVTalk { // Add the name and address to an array adapter to show in a ListView //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { + if(device.getName().compareTo(device_name) == 0) { this.device = device; return; } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 917dfb116..13e415c54 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -277,7 +277,7 @@ public class OPTelemetryService extends Service { Looper.prepare(); - BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index f5d40040b..1f647bd99 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -20,7 +20,7 @@ public class TcpUAVTalk { // Temporarily define fixed device name private String ip_address = "1"; - public final static int PORT = 9001; + private int port = 9001; private UAVTalk uavTalk; private boolean connected; @@ -28,8 +28,12 @@ public class TcpUAVTalk { public TcpUAVTalk(Context caller) { SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); ip_address = prefs.getString("ip_address","127.0.0.1"); + try { + port = Integer.decode(prefs.getString("port", "")); + } catch (NumberFormatException e) { + } - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -52,7 +56,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + port); InetAddress serverAddr = null; try { @@ -65,7 +69,7 @@ public class TcpUAVTalk { Socket socket = null; try { - socket = new Socket(serverAddr,PORT); + socket = new Socket(serverAddr,port); } catch (IOException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From 4e7d8bffc4268e4420b24e6933c19a53a5ce547f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:25 -0500 Subject: [PATCH 258/508] Update the sdk version --- androidgcs/AndroidManifest.xml | 2 +- androidgcs/project.properties | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index c18dc0cb1..40b08c328 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,7 +2,7 @@ - + diff --git a/androidgcs/project.properties b/androidgcs/project.properties index 5d85d779c..a43ea8cdc 100644 --- a/androidgcs/project.properties +++ b/androidgcs/project.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:13 +target=Google Inc.:Google APIs:16 From 8f98383fa598fd00bbd4f5f2765b0c1f28e5ae08 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:54 -0500 Subject: [PATCH 259/508] Check in a joystick gadget class --- .../Android/Widgets/DockPanel/DockPanel.java | 319 +++++++++++ .../Widgets/DockPanel/DockPosition.java | 5 + .../DragAndDrop/DragAndDropManager.java | 124 +++++ .../Widgets/DragAndDrop/DragSurface.java | 94 ++++ .../Widgets/DragAndDrop/DraggableItem.java | 44 ++ .../DragAndDrop/DraggableViewsFactory.java | 19 + .../Android/Widgets/DragAndDrop/DropZone.java | 67 +++ .../DragAndDrop/DropZoneEventsListener.java | 9 + .../Widgets/Joystick/DualJoystickView.java | 147 +++++ .../Joystick/JoystickClickedListener.java | 6 + .../Joystick/JoystickMovedListener.java | 7 + .../Widgets/Joystick/JoystickView.java | 521 ++++++++++++++++++ .../ThresholdEditText/ThresholdEditText.java | 169 ++++++ .../ThresholdTextChanged.java | 7 + .../Widgets/TilesLayout/SingleTileLayout.java | 68 +++ .../Widgets/TilesLayout/TilePosition.java | 63 +++ .../Widgets/TilesLayout/TilesLayout.java | 299 ++++++++++ .../TilesLayout/TilesLayoutPreset.java | 157 ++++++ 18 files changed, 2125 insertions(+) create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java new file mode 100644 index 000000000..e2397394e --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java @@ -0,0 +1,319 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +import android.content.Context; +import android.graphics.Color; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.LayoutInflater; +import android.view.View; +import android.view.animation.AccelerateInterpolator; +import android.view.animation.Animation; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; +import android.widget.ImageButton; +import android.widget.LinearLayout; + +public class DockPanel extends LinearLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "DockPanel"; + private DockPosition position; + private int contentLayoutId; + private int handleButtonDrawableId; + private Boolean isOpen; + private Boolean animationRunning; + private FrameLayout contentPlaceHolder; + private ImageButton toggleButton; + private int animationDuration; + + // ========================================= + // Constructors + // ========================================= + + public DockPanel(Context context, int contentLayoutId, + int handleButtonDrawableId, Boolean isOpen) { + super(context); + + this.contentLayoutId = contentLayoutId; + this.handleButtonDrawableId = handleButtonDrawableId; + this.isOpen = isOpen; + + Init(null); + } + + public DockPanel(Context context, AttributeSet attrs) { + super(context, attrs); + + // to prevent from crashing the designer + try { + Init(attrs); + } catch (Exception ex) { + } + } + + // ========================================= + // Initialization + // ========================================= + + private void Init(AttributeSet attrs) { + setDefaultValues(attrs); + + createHandleToggleButton(); + + // create the handle container + FrameLayout handleContainer = new FrameLayout(getContext()); + handleContainer.addView(toggleButton); + + // create and populate the panel's container, and inflate it + contentPlaceHolder = new FrameLayout(getContext()); + String infService = Context.LAYOUT_INFLATER_SERVICE; + LayoutInflater li = (LayoutInflater) getContext().getSystemService( + infService); + li.inflate(contentLayoutId, contentPlaceHolder, true); + + // setting the layout of the panel parameters according to the docking + // position + if (position == DockPosition.LEFT || position == DockPosition.RIGHT) { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + } else { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + } + + // adding the view to the parent layout according to docking position + if (position == DockPosition.RIGHT || position == DockPosition.BOTTOM) { + this.addView(handleContainer); + this.addView(contentPlaceHolder); + } else { + this.addView(contentPlaceHolder); + this.addView(handleContainer); + } + + if (!isOpen) { + contentPlaceHolder.setVisibility(GONE); + } + } + + private void setDefaultValues(AttributeSet attrs) { + // set default values + isOpen = true; + animationRunning = false; + animationDuration = 500; + setPosition(DockPosition.RIGHT); + + // Try to load values set by xml markup + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + animationDuration = attrs.getAttributeIntValue(namespace, + "animationDuration", 500); + contentLayoutId = attrs.getAttributeResourceValue(namespace, + "contentLayoutId", 0); + handleButtonDrawableId = attrs.getAttributeResourceValue( + namespace, "handleButtonDrawableResourceId", 0); + isOpen = attrs.getAttributeBooleanValue(namespace, "isOpen", true); + + // Enums are a bit trickier (needs to be parsed) + try { + position = DockPosition.valueOf(attrs.getAttributeValue( + namespace, "dockPosition").toUpperCase()); + setPosition(position); + } catch (Exception ex) { + // Docking to the left is the default behavior + setPosition(DockPosition.LEFT); + } + } + } + + private void createHandleToggleButton() { + toggleButton = new ImageButton(getContext()); + toggleButton.setPadding(0, 0, 0, 0); + toggleButton.setLayoutParams(new FrameLayout.LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + Gravity.CENTER)); + toggleButton.setBackgroundColor(Color.TRANSPARENT); + toggleButton.setImageResource(handleButtonDrawableId); + toggleButton.setOnClickListener(new OnClickListener() { + @Override + public void onClick(View v) { + toggle(); + } + }); + } + + private void setPosition(DockPosition position) { + this.position = position; + switch (position) { + case TOP: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.TOP); + break; + case RIGHT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.RIGHT); + break; + case BOTTOM: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.BOTTOM); + break; + case LEFT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.LEFT); + break; + } + } + + // ========================================= + // Public methods + // ========================================= + + public int getAnimationDuration() { + return animationDuration; + } + + public void setAnimationDuration(int milliseconds) { + animationDuration = milliseconds; + } + + public Boolean getIsRunning() { + return animationRunning; + } + + public void open() { + if (!animationRunning) { + Log.d(TAG, "Opening..."); + + Animation animation = createShowAnimation(); + this.setAnimation(animation); + animation.start(); + + isOpen = true; + } + } + + public void close() { + if (!animationRunning) { + Log.d(TAG, "Closing..."); + + Animation animation = createHideAnimation(); + this.setAnimation(animation); + animation.start(); + isOpen = false; + } + } + + public void toggle() { + if (isOpen) { + close(); + } else { + open(); + } + } + + // ========================================= + // Private methods + // ========================================= + + private Animation createHideAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, 0, -contentPlaceHolder + .getHeight()); + break; + case RIGHT: + animation = new TranslateAnimation(0, contentPlaceHolder + .getWidth(), 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, 0, contentPlaceHolder + .getHeight()); + break; + case LEFT: + animation = new TranslateAnimation(0, -contentPlaceHolder + .getWidth(), 0, 0); + break; + } + + animation.setDuration(animationDuration); + animation.setInterpolator(new AccelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + contentPlaceHolder.setVisibility(View.GONE); + animationRunning = false; + } + }); + return animation; + } + + private Animation createShowAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, -contentPlaceHolder + .getHeight(), 0); + break; + case RIGHT: + animation = new TranslateAnimation(contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, contentPlaceHolder + .getHeight(), 0); + break; + case LEFT: + animation = new TranslateAnimation(-contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + } + Log.d(TAG, "Animation duration: " + animationDuration); + animation.setDuration(animationDuration); + animation.setInterpolator(new DecelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + contentPlaceHolder.setVisibility(View.VISIBLE); + Log.d(TAG, "\"Show\" Animation started"); + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + animationRunning = false; + Log.d(TAG, "\"Show\" Animation ended"); + } + }); + return animation; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java new file mode 100644 index 000000000..59643dfc6 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java @@ -0,0 +1,5 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +public enum DockPosition { + TOP, BOTTOM, LEFT, RIGHT +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java new file mode 100644 index 000000000..d7e0c5e44 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java @@ -0,0 +1,124 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import java.util.ArrayList; + +import android.content.Context; +import android.view.MotionEvent; +import android.view.View; +import android.view.View.OnTouchListener; + +public class DragAndDropManager { + + // ========================================= + // Private members + // ========================================= + + protected static final String TAG = "DragAndDropManager"; + private static DragAndDropManager instance = null; + private ArrayList dropZones; + private OnTouchListener originalTouchListener; + private DragSurface dragSurface; + private DraggableItem draggedItem; + private DropZone activeDropZone; + + // ========================================= + // Protected Constructor + // ========================================= + + protected DragAndDropManager() { + // Exists only to defeat instantiation. + dropZones = new ArrayList(); + } + + // ========================================= + // Public Properties + // ========================================= + + public static DragAndDropManager getInstance() { + if (instance == null) { + instance = new DragAndDropManager(); + } + return instance; + } + + public Context getContext() { + if (dragSurface == null) + return null; + + return dragSurface.getContext(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void init(DragSurface surface) { + dragSurface = surface; + clearDropZones(); + } + + public void clearDropZones() { + dropZones.clear(); + } + + public void addDropZone(DropZone dropZone) { + dropZones.add(dropZone); + } + + + public void startDragging(OnTouchListener originalListener, DraggableItem draggedItem) { + originalTouchListener = originalListener; + this.draggedItem = draggedItem; + draggedItem.getSource().setOnTouchListener(new OnTouchListener() { + + @Override + public boolean onTouch(View v, MotionEvent event) { + int[] location = new int[2]; + v.getLocationOnScreen(location); + event.offsetLocation(location[0], location[1]); + invalidateDropZones((int)event.getX(), (int)event.getY()); + return dragSurface.onTouchEvent(event); + } + }); + + dragSurface.startDragging(draggedItem); + } + + + // ========================================= + // Protected Methods + // ========================================= + + protected void invalidateDropZones(int x, int y) { + if (activeDropZone != null) { + if (!activeDropZone.isOver(x, y)) { + activeDropZone.getListener().OnDragZoneLeft(activeDropZone, draggedItem); + activeDropZone = null; + } + else { + // we are still over the same drop zone, no need to check other drop zones + return; + } + } + + for (DropZone dropZone : dropZones) { + if (dropZone.isOver(x, y)) { + activeDropZone = dropZone; + dropZone.getListener().OnDragZoneEntered(activeDropZone, draggedItem); + break; + } + } + } + + protected void stoppedDragging() { + if (activeDropZone != null) { + activeDropZone.getListener().OnDropped(activeDropZone, draggedItem); + } + + // Registering the "old" listener to the view that initiated this drag session + draggedItem.getSource().setOnTouchListener(originalTouchListener); + draggedItem = null; + activeDropZone = null; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java new file mode 100644 index 000000000..aebb9d481 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java @@ -0,0 +1,94 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.Gravity; +import android.view.MotionEvent; +import android.widget.FrameLayout; + +public class DragSurface extends FrameLayout { + + private float draggedViewHalfHeight; + private float draggedViewHalfWidth; + private int framesCount; + + private Boolean isDragging; + private DraggableItem draggedItem; + + public DragSurface(Context context, AttributeSet attrs) { + super(context, attrs); + isDragging = false; + } + + // ========================================= + // Touch Events Listener + // ========================================= + + @Override + public boolean onTouchEvent(MotionEvent event) { + if (isDragging && event.getAction() == MotionEvent.ACTION_UP) { + // Dragging ended + removeAllViews(); + isDragging = false; + + DragAndDropManager.getInstance().stoppedDragging(); + } + + if (isDragging && event.getAction() == MotionEvent.ACTION_MOVE) { + // Move the dragged view to it's new position + repositionView(event.getX(), event.getY()); + + // Mark this event as handled (so that other UI elements will not intercept it) + return true; + } + + return false; + } + + public void startDragging(DraggableItem draggableItem) { + this.draggedItem = draggableItem; + this.draggedItem.getDraggedView().setVisibility(INVISIBLE); + isDragging = true; + addView(this.draggedItem.getDraggedView()); + //repositionView(x, y); + framesCount = 0; + } + + private void repositionView(float x, float y) { + draggedViewHalfHeight = draggedItem.getDraggedView().getHeight() / 2f; + draggedViewHalfWidth = draggedItem.getDraggedView().getWidth() / 2f; + + // If the dragged view was not drawn yet, skip this phase + if (draggedViewHalfHeight == 0 || draggedViewHalfWidth == 0) + return; + + framesCount++; + + //Log.d(TAG, "Original = (x=" + x + ", y=" + y + ")"); + //Log.d(TAG, "Size (W=" + draggedViewHalfWidth + ", H=" + draggedViewHalfHeight + ")"); + + x = x - draggedViewHalfWidth; + y = y - draggedViewHalfHeight; + + x = Math.max(x, 0); + x = Math.min(x, getWidth() - draggedViewHalfWidth * 2); + + y = Math.max(y, 0); + y = Math.min(y, getHeight() - draggedViewHalfHeight * 2); + + //Log.d(TAG, "Moving view to (x=" + x + ", y=" + y + ")"); + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams(LayoutParams.WRAP_CONTENT, + LayoutParams.WRAP_CONTENT, Gravity.TOP + Gravity.LEFT); + + lp.setMargins((int)x, (int)y, 0, 0); + draggedItem.getDraggedView().setLayoutParams(lp); + + // hte first couple of dragged frame's positions are not calculated correctly, + // so we have a threshold before making the dragged view visible again + if (framesCount < 2) + return; + + draggedItem.getDraggedView().setVisibility(VISIBLE); + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java new file mode 100644 index 000000000..d0c8b7e25 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java @@ -0,0 +1,44 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DraggableItem { + + // ========================================= + // Private members + // ========================================= + + private View source; + private View draggedView; + private Object tag; + + // ========================================= + // Constructor + // ========================================= + + public DraggableItem(View source, View draggedItem) { + this.source = source; + this.draggedView = draggedItem; + } + + // ========================================= + // Public properties + // ========================================= + + public Object getTag() { + return tag; + } + + public void setTag(Object tag) { + this.tag = tag; + } + + public View getSource() { + return source; + } + + public View getDraggedView() { + return draggedView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java new file mode 100644 index 000000000..246b2392f --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java @@ -0,0 +1,19 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.view.View; +import android.widget.TextView; +import android.widget.TableLayout.LayoutParams; + +public class DraggableViewsFactory { + + public static View getLabel(String text) { + Context context = DragAndDropManager.getInstance().getContext(); + TextView textView = new TextView(context); + textView.setText(text); + textView.setLayoutParams(new LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + //textView.setGravity(Gravity.TOP + Gravity.LEFT); + return textView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java new file mode 100644 index 000000000..06a8caa17 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java @@ -0,0 +1,67 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DropZone { + + // ========================================= + // Private members + // ========================================= + + private View view; + private DropZoneEventsListener listener; + private int left, top, width, height; + private Boolean dimansionsCalculated; + + // ========================================= + // Constructor + // ========================================= + + public DropZone(View view, DropZoneEventsListener listener) { + this.view = view; + this.listener = listener; + dimansionsCalculated = false; + } + + // ========================================= + // Public properties + // ========================================= + + public View getView() { + return view; + } + + // ========================================= + // Public methods + // ========================================= + + public Boolean isOver(int x, int y) { + if (!dimansionsCalculated) + calculateDimensions(); + + Boolean isOver = (x >= left && x <= (left + width)) && + (y >= top && y <= (top + height)); + + //Log.d("DragZone", "x=" +x + ", left=" + left + ", y=" + y + ", top=" + top + " width=" + width + ", height=" + height + ", isover=" + isOver); + + return isOver; + } + + // ========================================= + // Protected & Private methods + // ========================================= + + protected DropZoneEventsListener getListener() { + return listener; + } + + private void calculateDimensions() { + int[] location = new int[2]; + view.getLocationOnScreen(location); + left = location[0]; + top = location[1]; + width = view.getWidth(); + height = view.getHeight(); + dimansionsCalculated = true; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java new file mode 100644 index 000000000..828a1cbf2 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java @@ -0,0 +1,9 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +public interface DropZoneEventsListener { + + void OnDragZoneEntered(DropZone zone, DraggableItem item); + void OnDragZoneLeft(DropZone zone, DraggableItem item); + void OnDropped(DropZone zone, DraggableItem item); + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java new file mode 100644 index 000000000..bb419d404 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java @@ -0,0 +1,147 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.MotionEvent; +import android.view.View; +import android.view.ViewGroup; +import android.widget.LinearLayout; + +public class DualJoystickView extends LinearLayout { + @SuppressWarnings("unused") + private static final String TAG = DualJoystickView.class.getSimpleName(); + + private final boolean D = false; + private Paint dbgPaint1; + + private JoystickView stickL; + private JoystickView stickR; + + private View pad; + + public DualJoystickView(Context context) { + super(context); + stickL = new JoystickView(context); + stickR = new JoystickView(context); + initDualJoystickView(); + } + + public DualJoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + stickL = new JoystickView(context, attrs); + stickR = new JoystickView(context, attrs); + initDualJoystickView(); + } + + private void initDualJoystickView() { + setOrientation(LinearLayout.HORIZONTAL); + + if ( D ) { + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.CYAN); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + } + + pad = new View(getContext()); + } + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + super.onMeasure(widthMeasureSpec, heightMeasureSpec); + removeView(stickL); + removeView(stickR); + + float padW = getMeasuredWidth()-(getMeasuredHeight()*2); + int joyWidth = (int) ((getMeasuredWidth()-padW)/2); + LayoutParams joyLParams = new LayoutParams(joyWidth,getMeasuredHeight()); + + stickL.setLayoutParams(joyLParams); + stickR.setLayoutParams(joyLParams); + + stickL.TAG = "L"; + stickR.TAG = "R"; + stickL.setPointerId(JoystickView.INVALID_POINTER_ID); + stickR.setPointerId(JoystickView.INVALID_POINTER_ID); + + addView(stickL); + + ViewGroup.LayoutParams padLParams = new ViewGroup.LayoutParams((int) padW,getMeasuredHeight()); + removeView(pad); + pad.setLayoutParams(padLParams); + addView(pad); + + addView(stickR); + } + + @Override + protected void onLayout(boolean changed, int l, int t, int r, int b) { + super.onLayout(changed, l, t, r, b); + stickR.setTouchOffset(stickR.getLeft(), stickR.getTop()); + } + + public void setAutoReturnToCenter(boolean left, boolean right) { + stickL.setAutoReturnToCenter(left); + stickR.setAutoReturnToCenter(right); + } + + public void setOnJostickMovedListener(JoystickMovedListener left, JoystickMovedListener right) { + stickL.setOnJostickMovedListener(left); + stickR.setOnJostickMovedListener(right); + } + + public void setOnJostickClickedListener(JoystickClickedListener left, JoystickClickedListener right) { + stickL.setOnJostickClickedListener(left); + stickR.setOnJostickClickedListener(right); + } + + public void setYAxisInverted(boolean leftYAxisInverted, boolean rightYAxisInverted) { + stickL.setYAxisInverted(leftYAxisInverted); + stickL.setYAxisInverted(rightYAxisInverted); + } + + public void setMovementConstraint(int movementConstraint) { + stickL.setMovementConstraint(movementConstraint); + stickR.setMovementConstraint(movementConstraint); + } + + public void setMovementRange(float movementRangeLeft, float movementRangeRight) { + stickL.setMovementRange(movementRangeLeft); + stickR.setMovementRange(movementRangeRight); + } + + public void setMoveResolution(float leftMoveResolution, float rightMoveResolution) { + stickL.setMoveResolution(leftMoveResolution); + stickR.setMoveResolution(rightMoveResolution); + } + + public void setUserCoordinateSystem(int leftCoordinateSystem, int rightCoordinateSystem) { + stickL.setUserCoordinateSystem(leftCoordinateSystem); + stickR.setUserCoordinateSystem(rightCoordinateSystem); + } + + @Override + protected void dispatchDraw(Canvas canvas) { + super.dispatchDraw(canvas); + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + } + } + + @Override + public boolean dispatchTouchEvent(MotionEvent ev) { + boolean l = stickL.dispatchTouchEvent(ev); + boolean r = stickR.dispatchTouchEvent(ev); + return l || r; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + boolean l = stickL.onTouchEvent(ev); + boolean r = stickR.onTouchEvent(ev); + return l || r; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java new file mode 100644 index 000000000..128828980 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java @@ -0,0 +1,6 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickClickedListener { + public void OnClicked(); + public void OnReleased(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java new file mode 100644 index 000000000..346f2efed --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickMovedListener { + public void OnMoved(int pan, int tilt); + public void OnReleased(); + public void OnReturnedToCenter(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java new file mode 100644 index 000000000..bab74e5a7 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java @@ -0,0 +1,521 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.HapticFeedbackConstants; +import android.view.MotionEvent; +import android.view.View; + +public class JoystickView extends View { + public static final int INVALID_POINTER_ID = -1; + + // ========================================= + // Private Members + // ========================================= + private final boolean D = false; + String TAG = "JoystickView"; + + private Paint dbgPaint1; + private Paint dbgPaint2; + + private Paint bgPaint; + private Paint handlePaint; + + private int innerPadding; + private int bgRadius; + private int handleRadius; + private int movementRadius; + private int handleInnerBoundaries; + + private JoystickMovedListener moveListener; + private JoystickClickedListener clickListener; + + //# of pixels movement required between reporting to the listener + private float moveResolution; + + private boolean yAxisInverted; + private boolean autoReturnToCenter; + + //Max range of movement in user coordinate system + public final static int CONSTRAIN_BOX = 0; + public final static int CONSTRAIN_CIRCLE = 1; + private int movementConstraint; + private float movementRange; + + public final static int COORDINATE_CARTESIAN = 0; //Regular cartesian coordinates + public final static int COORDINATE_DIFFERENTIAL = 1; //Uses polar rotation of 45 degrees to calc differential drive paramaters + private int userCoordinateSystem; + + //Records touch pressure for click handling + private float touchPressure; + private boolean clicked; + private float clickThreshold; + + //Last touch point in view coordinates + private int pointerId = INVALID_POINTER_ID; + private float touchX, touchY; + + //Last reported position in view coordinates (allows different reporting sensitivities) + private float reportX, reportY; + + //Handle center in view coordinates + private float handleX, handleY; + + //Center of the view in view coordinates + private int cX, cY; + + //Size of the view in view coordinates + private int dimX, dimY; + + //Cartesian coordinates of last touch point - joystick center is (0,0) + private int cartX, cartY; + + //Polar coordinates of the touch point from joystick center + private double radial; + private double angle; + + //User coordinates of last touch point + private int userX, userY; + + //Offset co-ordinates (used when touch events are received from parent's coordinate origin) + private int offsetX; + private int offsetY; + + // ========================================= + // Constructors + // ========================================= + + public JoystickView(Context context) { + super(context); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs, int defStyle) { + super(context, attrs, defStyle); + initJoystickView(); + } + + // ========================================= + // Initialization + // ========================================= + + private void initJoystickView() { + setFocusable(true); + + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.RED); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + + dbgPaint2 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint2.setColor(Color.GREEN); + dbgPaint2.setStrokeWidth(1); + dbgPaint2.setStyle(Paint.Style.STROKE); + + bgPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + bgPaint.setColor(Color.GRAY); + bgPaint.setStrokeWidth(1); + bgPaint.setStyle(Paint.Style.FILL_AND_STROKE); + + handlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + handlePaint.setColor(Color.DKGRAY); + handlePaint.setStrokeWidth(1); + handlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + + innerPadding = 10; + + setMovementRange(10); + setMoveResolution(1.0f); + setClickThreshold(0.4f); + setYAxisInverted(true); + setUserCoordinateSystem(COORDINATE_CARTESIAN); + setAutoReturnToCenter(true); + } + + public void setAutoReturnToCenter(boolean autoReturnToCenter) { + this.autoReturnToCenter = autoReturnToCenter; + } + + public boolean isAutoReturnToCenter() { + return autoReturnToCenter; + } + + public void setUserCoordinateSystem(int userCoordinateSystem) { + if (userCoordinateSystem < COORDINATE_CARTESIAN || movementConstraint > COORDINATE_DIFFERENTIAL) + Log.e(TAG, "invalid value for userCoordinateSystem"); + else + this.userCoordinateSystem = userCoordinateSystem; + } + + public int getUserCoordinateSystem() { + return userCoordinateSystem; + } + + public void setMovementConstraint(int movementConstraint) { + if (movementConstraint < CONSTRAIN_BOX || movementConstraint > CONSTRAIN_CIRCLE) + Log.e(TAG, "invalid value for movementConstraint"); + else + this.movementConstraint = movementConstraint; + } + + public int getMovementConstraint() { + return movementConstraint; + } + + public boolean isYAxisInverted() { + return yAxisInverted; + } + + public void setYAxisInverted(boolean yAxisInverted) { + this.yAxisInverted = yAxisInverted; + } + + /** + * Set the pressure sensitivity for registering a click + * @param clickThreshold threshold 0...1.0f inclusive. 0 will cause clicks to never be reported, 1.0 is a very hard click + */ + public void setClickThreshold(float clickThreshold) { + if (clickThreshold < 0 || clickThreshold > 1.0f) + Log.e(TAG, "clickThreshold must range from 0...1.0f inclusive"); + else + this.clickThreshold = clickThreshold; + } + + public float getClickThreshold() { + return clickThreshold; + } + + public void setMovementRange(float movementRange) { + this.movementRange = movementRange; + } + + public float getMovementRange() { + return movementRange; + } + + public void setMoveResolution(float moveResolution) { + this.moveResolution = moveResolution; + } + + public float getMoveResolution() { + return moveResolution; + } + + // ========================================= + // Public Methods + // ========================================= + + public void setOnJostickMovedListener(JoystickMovedListener listener) { + this.moveListener = listener; + } + + public void setOnJostickClickedListener(JoystickClickedListener listener) { + this.clickListener = listener; + } + + // ========================================= + // Drawing Functionality + // ========================================= + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + // Here we make sure that we have a perfect circle + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + setMeasuredDimension(measuredWidth, measuredHeight); + } + + @Override + protected void onLayout(boolean changed, int left, int top, int right, int bottom) { + super.onLayout(changed, left, top, right, bottom); + + int d = Math.min(getMeasuredWidth(), getMeasuredHeight()); + + dimX = d; + dimY = d; + + cX = d / 2; + cY = d / 2; + + bgRadius = dimX/2 - innerPadding; + handleRadius = (int)(d * 0.25); + handleInnerBoundaries = handleRadius; + movementRadius = Math.min(cX, cY) - handleInnerBoundaries; + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + if (specMode == MeasureSpec.UNSPECIFIED) { + // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + @Override + protected void onDraw(Canvas canvas) { + canvas.save(); + // Draw the background + canvas.drawCircle(cX, cY, bgRadius, bgPaint); + + // Draw the handle + handleX = touchX + cX; + handleY = touchY + cY; + canvas.drawCircle(handleX, handleY, handleRadius, handlePaint); + + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + + canvas.drawCircle(handleX, handleY, 3, dbgPaint1); + + if ( movementConstraint == CONSTRAIN_CIRCLE ) { + canvas.drawCircle(cX, cY, this.movementRadius, dbgPaint1); + } + else { + canvas.drawRect(cX-movementRadius, cY-movementRadius, cX+movementRadius, cY+movementRadius, dbgPaint1); + } + + //Origin to touch point + canvas.drawLine(cX, cY, handleX, handleY, dbgPaint2); + + int baseY = (int) (touchY < 0 ? cY + handleRadius : cY - handleRadius); + canvas.drawText(String.format("%s (%.0f,%.0f)", TAG, touchX, touchY), handleX-20, baseY-7, dbgPaint2); + canvas.drawText("("+ String.format("%.0f, %.1f", radial, angle * 57.2957795) + (char) 0x00B0 + ")", handleX-20, baseY+15, dbgPaint2); + } + +// Log.d(TAG, String.format("touch(%f,%f)", touchX, touchY)); +// Log.d(TAG, String.format("onDraw(%.1f,%.1f)\n\n", handleX, handleY)); + canvas.restore(); + } + + // Constrain touch within a box + private void constrainBox() { + touchX = Math.max(Math.min(touchX, movementRadius), -movementRadius); + touchY = Math.max(Math.min(touchY, movementRadius), -movementRadius); + } + + // Constrain touch within a circle + private void constrainCircle() { + float diffX = touchX; + float diffY = touchY; + double radial = Math.sqrt((diffX*diffX) + (diffY*diffY)); + if ( radial > movementRadius ) { + touchX = (int)((diffX / radial) * movementRadius); + touchY = (int)((diffY / radial) * movementRadius); + } + } + + public void setPointerId(int id) { + this.pointerId = id; + } + + public int getPointerId() { + return pointerId; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + final int action = ev.getAction(); + switch (action & MotionEvent.ACTION_MASK) { + case MotionEvent.ACTION_MOVE: { + return processMoveEvent(ev); + } + case MotionEvent.ACTION_CANCEL: + case MotionEvent.ACTION_UP: { + if ( pointerId != INVALID_POINTER_ID ) { +// Log.d(TAG, "ACTION_UP"); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + } + break; + } + case MotionEvent.ACTION_POINTER_UP: { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + if ( pointerId == this.pointerId ) { +// Log.d(TAG, "ACTION_POINTER_UP: " + pointerId); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + return true; + } + } + break; + } + case MotionEvent.ACTION_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + int x = (int) ev.getX(); + if ( x >= offsetX && x < offsetX + dimX ) { + setPointerId(ev.getPointerId(0)); +// Log.d(TAG, "ACTION_DOWN: " + getPointerId()); + return true; + } + } + break; + } + case MotionEvent.ACTION_POINTER_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + int x = (int) ev.getX(pointerId); + if ( x >= offsetX && x < offsetX + dimX ) { +// Log.d(TAG, "ACTION_POINTER_DOWN: " + pointerId); + setPointerId(pointerId); + return true; + } + } + break; + } + } + return false; + } + + private boolean processMoveEvent(MotionEvent ev) { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = ev.findPointerIndex(pointerId); + + // Translate touch position to center of view + float x = ev.getX(pointerIndex); + touchX = x - cX - offsetX; + float y = ev.getY(pointerIndex); + touchY = y - cY - offsetY; + +// Log.d(TAG, String.format("ACTION_MOVE: (%03.0f, %03.0f) => (%03.0f, %03.0f)", x, y, touchX, touchY)); + + reportOnMoved(); + invalidate(); + + touchPressure = ev.getPressure(pointerIndex); + reportOnPressure(); + + return true; + } + return false; + } + + private void reportOnMoved() { + if ( movementConstraint == CONSTRAIN_CIRCLE ) + constrainCircle(); + else + constrainBox(); + + calcUserCoordinates(); + + if (moveListener != null) { + boolean rx = Math.abs(touchX - reportX) >= moveResolution; + boolean ry = Math.abs(touchY - reportY) >= moveResolution; + if (rx || ry) { + this.reportX = touchX; + this.reportY = touchY; + +// Log.d(TAG, String.format("moveListener.OnMoved(%d,%d)", (int)userX, (int)userY)); + moveListener.OnMoved(userX, userY); + } + } + } + + private void calcUserCoordinates() { + //First convert to cartesian coordinates + cartX = (int)(touchX / movementRadius * movementRange); + cartY = (int)(touchY / movementRadius * movementRange); + + radial = Math.sqrt((cartX*cartX) + (cartY*cartY)); + angle = Math.atan2(cartY, cartX); + + //Invert Y axis if requested + if ( !yAxisInverted ) + cartY *= -1; + + if ( userCoordinateSystem == COORDINATE_CARTESIAN ) { + userX = cartX; + userY = cartY; + } + else if ( userCoordinateSystem == COORDINATE_DIFFERENTIAL ) { + userX = cartY + cartX / 4; + userY = cartY - cartX / 4; + + if ( userX < -movementRange ) + userX = (int)-movementRange; + if ( userX > movementRange ) + userX = (int)movementRange; + + if ( userY < -movementRange ) + userY = (int)-movementRange; + if ( userY > movementRange ) + userY = (int)movementRange; + } + + } + + //Simple pressure click + private void reportOnPressure() { +// Log.d(TAG, String.format("touchPressure=%.2f", this.touchPressure)); + if ( clickListener != null ) { + if ( clicked && touchPressure < clickThreshold ) { + clickListener.OnReleased(); + this.clicked = false; +// Log.d(TAG, "reset click"); + invalidate(); + } + else if ( !clicked && touchPressure >= clickThreshold ) { + clicked = true; + clickListener.OnClicked(); +// Log.d(TAG, "click"); + invalidate(); + performHapticFeedback(HapticFeedbackConstants.VIRTUAL_KEY); + } + } + } + + private void returnHandleToCenter() { + if ( autoReturnToCenter ) { + final int numberOfFrames = 5; + final double intervalsX = (0 - touchX) / numberOfFrames; + final double intervalsY = (0 - touchY) / numberOfFrames; + + for (int i = 0; i < numberOfFrames; i++) { + final int j = i; + postDelayed(new Runnable() { + @Override + public void run() { + touchX += intervalsX; + touchY += intervalsY; + + reportOnMoved(); + invalidate(); + + if (moveListener != null && j == numberOfFrames - 1) { + moveListener.OnReturnedToCenter(); + } + } + }, i * 40); + } + + if (moveListener != null) { + moveListener.OnReleased(); + } + } + } + + public void setTouchOffset(int x, int y) { + offsetX = x; + offsetY = y; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java new file mode 100644 index 000000000..5fbd76f46 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java @@ -0,0 +1,169 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.content.Context; +import android.os.Handler; +import android.text.Editable; +import android.text.TextWatcher; +import android.util.AttributeSet; +import android.widget.EditText; + +public class ThresholdEditText extends EditText { + + // ========================================= + // Private members + // ========================================= + + private int threshold; + private ThresholdTextChanged thresholdTextChanged; + private Handler handler; + private Runnable invoker; + private boolean thresholdDisabledOnEmptyInput; + + + // ========================================= + // Constructors + // ========================================= + + public ThresholdEditText(Context context) { + super(context); + initAttributes(null); + init(); + } + + public ThresholdEditText(Context context, AttributeSet attrs) { + super(context, attrs); + initAttributes(attrs); + init(); + } + + + // ========================================= + // Public properties + // ========================================= + + /** + * Get the current threshold value + */ + public int getThreshold() { + return threshold; + } + + /** + * Set the threshold value (in milliseconds) + * + * @param threshold + * Threshold value + */ + public void setThreshold(int threshold) { + this.threshold = threshold; + } + + /** + * @return True = the callback will fire immediately when the content of the + * EditText is emptied False = The threshold will be used even on + * empty input + */ + public boolean getThresholdDisabledOnEmptyInput() { + return thresholdDisabledOnEmptyInput; + } + + /** + * @param thresholdDisabledOnEmptyInput + * Set to true if you want the callback to fire immediately when + * the content of the EditText is emptied + */ + public void setThresholdDisabledOnEmptyInput( + boolean thresholdDisabledOnEmptyInput) { + this.thresholdDisabledOnEmptyInput = thresholdDisabledOnEmptyInput; + } + + /** + * Set the callback to the OnThresholdTextChanged event + * + * @param listener + */ + public void setOnThresholdTextChanged(ThresholdTextChanged listener) { + this.thresholdTextChanged = listener; + } + + // ========================================= + // Private / Protected methods + // ========================================= + + /** + * Load properties values from xml layout + */ + private void initAttributes(AttributeSet attrs) { + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + // Load values to local members + this.threshold = attrs.getAttributeIntValue(namespace, "threshold", + 500); + this.thresholdDisabledOnEmptyInput = attrs.getAttributeBooleanValue( + namespace, "disableThresholdOnEmptyInput", true); + } else { + // Default threshold value is 0.5 seconds + threshold = 500; + + // Default behaviour on emptied text - no threshold + thresholdDisabledOnEmptyInput = true; + } + } + + /** + * Initialize the private members with default values + */ + private void init() { + + handler = new Handler(); + + invoker = new Runnable() { + + @Override + public void run() { + invokeCallback(); + } + + }; + + this.addTextChangedListener(new TextWatcher() { + + @Override + public void afterTextChanged(Editable s) { + } + + @Override + public void beforeTextChanged(CharSequence s, int start, int count, + int after) { + } + + @Override + public void onTextChanged(CharSequence s, int start, int before, + int count) { + + // Remove any existing pending callbacks + handler.removeCallbacks(invoker); + + if (s.length() == 0 && thresholdDisabledOnEmptyInput) { + // The text is empty, so invoke the callback immediately + invoker.run(); + } else { + // Post a new delayed callback + handler.postDelayed(invoker, threshold); + } + } + + }); + } + + /** + * Invoking the callback on the listener provided (if provided) + */ + private void invokeCallback() { + if (thresholdTextChanged != null) { + thresholdTextChanged.onThersholdTextChanged(this.getText()); + } + } + +} \ No newline at end of file diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java new file mode 100644 index 000000000..145f6547b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.text.Editable; + +public interface ThresholdTextChanged { + void onThersholdTextChanged(Editable text); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java new file mode 100644 index 000000000..d2f3be2d3 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java @@ -0,0 +1,68 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.FrameLayout; + +public class SingleTileLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private TilePosition position; + private long timestamp; + + // ========================================= + // Constructors + // ========================================= + + public SingleTileLayout(Context context) { + super(context); + } + + public SingleTileLayout(Context context, AttributeSet attrs) { + super(context, attrs); + } + + + // ========================================= + // Public Methods + // ========================================= + + public TilePosition getPosition() { + return position; + } + + public void setPosition(TilePosition position) { + this.position = position; + } + + public long getTimestamp() { + return this.timestamp; + } + + // ========================================= + // Overrides + // ========================================= + + @Override + public void addView(View child) { + super.addView(child); + timestamp = java.lang.System.currentTimeMillis(); + } + + @Override + public void removeAllViews() { + super.removeAllViews(); + timestamp = 0; + } + + @Override + public void removeView(View view) { + super.removeView(view); + timestamp = 0; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java new file mode 100644 index 000000000..04bf0c1d4 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java @@ -0,0 +1,63 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + + +public class TilePosition { + + // ========================================= + // Private Members + // ========================================= + + private float x, y, height, width; + + // ========================================= + // Constructors + // ========================================= + + public TilePosition(float x, float y, float width, float height) { + this.x = x; + this.y = y; + this.height = height; + this.width = width; + } + + // ========================================= + // Public Properties + // ========================================= + + public float getX() { + return x; + } + + public float getY() { + return y; + } + + public float getHeight() { + return height; + } + + public float getWidth() { + return width; + } + + + // ========================================= + // Public Methods + // ========================================= + + public Boolean equals(TilePosition position) { + if (position == null) + return false; + + return this.x == position.x && + this.y == position.y && + this.height == position.height && + this.width == position.width; + } + + @Override + public String toString() { + return "TilePosition = [X: " + x + ", Y: " + y + ", Height: " + height + ", Width: " + width + "]"; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java new file mode 100644 index 000000000..c1728faff --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java @@ -0,0 +1,299 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.ArrayList; +import java.util.List; + +import android.R; +import android.content.Context; +import android.graphics.Color; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.View; +import android.view.animation.AlphaAnimation; +import android.view.animation.Animation; +import android.view.animation.AnimationSet; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.ScaleAnimation; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; + +public class TilesLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "TilesLayout"; + private int animatedTransitionDuration; + private List tiles; + private TilesLayoutPreset preset; + private int tileBackgroundResourceId; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayout(Context context) { + super(context); + Init(null); + } + + public TilesLayout(Context context, AttributeSet attrs) { + super(context, attrs); + Init(attrs); + } + + + // ========================================= + // Public Properties + // ========================================= + + public void setPreset(TilesLayoutPreset preset) { + try { + rebuildLayout(preset); + this.preset = preset; + } + catch (Exception ex) { + Log.e(TAG, "Failed to set layout preset", ex); + } + } + + public TilesLayoutPreset getPreset() { + return this.preset; + } + + public int getAnimatedTransitionDuration() { + return animatedTransitionDuration; + } + + public void setAnimatedTransitionDuration(int animatedTransitionDuration) { + this.animatedTransitionDuration = animatedTransitionDuration; + } + + public int getTileBackgroundResourceId() { + return tileBackgroundResourceId; + } + + public void setTileBackgroundResourceId(int tileBackgroundResourceId) { + this.tileBackgroundResourceId = tileBackgroundResourceId; + } + + // ========================================= + // Public Methods + // ========================================= + + public void addContent(View view) { + for (int i = 0; i < tiles.size(); i++) { + if (tiles.get(i).getChildCount() == 0) { + tiles.get(i).addView(view); + return; + } + } + // No available space for the new view... + // TODO: Take the tile with the smallest time stamp and place the new view in it + } + + public void clearView(int tileId) { + if (tiles.size() < tileId) { + tiles.get(tileId).removeAllViews(); + } + } + + // ========================================= + // Private Methods + // ========================================= + + private void Init(AttributeSet attrs) { + animatedTransitionDuration = 750; + tileBackgroundResourceId = R.drawable.edit_text; + tiles = new ArrayList(); + } + + + private void rebuildLayout(TilesLayoutPreset preset) { + ArrayList positions = buildViewsPositions(preset); + + // We need to transform the current layout, to the new layout + int extraViews = tiles.size() - positions.size(); + if (extraViews > 0) { + // Remove the extra views + while(tiles.size() - positions.size() > 0) { + int lastViewPosition = tiles.size() - 1; + removeView(tiles.get(lastViewPosition)); + tiles.remove(lastViewPosition); + } + } else { + // Add the extra views + for (int i = tiles.size(); i< positions.size(); i++) { + TilePosition newTilePosition = positions.get(i); + SingleTileLayout tile = new SingleTileLayout(getContext()); + tile.setBackgroundResource(tileBackgroundResourceId); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)newTilePosition.getWidth(), + (int)newTilePosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)newTilePosition.getX(), + (int)newTilePosition.getY(), 0, 0); + + tile.setLayoutParams(lp); + + tiles.add(tile); + addView(tile); + } + } + // There is a bug in the animation-set, so we'll not animate + animateChange(positions); + + // Regular repositioning (no animation) + //processChange(positions); + } + + + + private ArrayList buildViewsPositions(TilesLayoutPreset preset) { + int width = getWidth(); + int height = getHeight(); + + Log.d(TAG, "Container's Dimensions = Width: " + width + ", Height: " + height); + ArrayList actualPositions = new ArrayList(); + for (TilePosition position : preset.getTilePositions()) { + + int tileX = (int) Math.round(width * ((float)position.getX() / 100.0)); + int tileY = (int) Math.round(height * ((float)position.getY() / 100.0)); + int tileWidth = (int) Math.round(width * ((float)position.getWidth() / 100.0)); + int tileHeight = (int) Math.round(height * ((float)position.getHeight() / 100.0)); + + TilePosition actualPosition = new TilePosition(tileX, tileY, tileWidth, tileHeight); + actualPositions.add(actualPosition); + + Log.d(TAG, "New tile created - X: " + tileX + ", Y: " + tileY + ", Width: " + tileWidth + ", Height: " + tileHeight); + } + return actualPositions; + } + + + @SuppressWarnings("unused") + private void processChange(ArrayList positions) { + for (int i = 0; i < tiles.size(); i++) { + final SingleTileLayout currentTile = tiles.get(i); + final TilePosition targetPosition = positions.get(i); + currentTile.setPosition(targetPosition); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + } + } + + + private void animateChange(ArrayList positions) { + AnimationSet animationSet = new AnimationSet(true); + DecelerateInterpolator decelerateInterpolator = new DecelerateInterpolator(); + + for (int i = 0; i < tiles.size(); i++) { + AnimationSet scaleAndMove = new AnimationSet(true); + scaleAndMove.setFillAfter(true); + + final SingleTileLayout currentTile = tiles.get(i); + TilePosition currentPosition = currentTile.getPosition(); + final TilePosition targetPosition = positions.get(i); + + if (currentPosition == null) { + AlphaAnimation alphaAnimation = new AlphaAnimation(0, 1); + alphaAnimation.setDuration(animatedTransitionDuration); + alphaAnimation.setStartOffset(0); + currentTile.setAnimation(alphaAnimation); + + scaleAndMove.addAnimation(alphaAnimation); + } + + currentTile.setPosition(targetPosition); + + if (!targetPosition.equals(currentPosition)) { + float toXDelta = 0, toYDelta = 0; + if (currentPosition != null) { + // Calculate new position + toXDelta = targetPosition.getX() - currentPosition.getX(); + toYDelta = targetPosition.getY() - currentPosition.getY(); + + // Factor in the scaling animation + toXDelta = toXDelta / (targetPosition.getWidth() / currentPosition.getWidth()); + toYDelta = toYDelta / (targetPosition.getHeight() / currentPosition.getHeight()); + } + + // Move + TranslateAnimation moveAnimation = new TranslateAnimation(0, toXDelta, 0, toYDelta); + moveAnimation.setDuration(animatedTransitionDuration); + moveAnimation.setStartOffset(0); + moveAnimation.setFillAfter(true); + moveAnimation.setInterpolator(decelerateInterpolator); + scaleAndMove.addAnimation(moveAnimation); + + // Physically move the tile when the animation ends + scaleAndMove.setAnimationListener(new AnimationListener() { + + @Override + public void onAnimationStart(Animation animation) { } + + @Override + public void onAnimationRepeat(Animation animation) { } + + @Override + public void onAnimationEnd(Animation animation) { + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + + // The following null animation just gets rid of screen flicker + animation = new TranslateAnimation(0.0f, 0.0f, 0.0f, 0.0f); + animation.setDuration(1); + currentTile.startAnimation(animation); + } + }); + + // Scale + if (currentPosition != null) { + ScaleAnimation scaleAnimation = + new ScaleAnimation(1, + targetPosition.getWidth() / currentPosition.getWidth(), + 1, + targetPosition.getHeight() / currentPosition.getHeight(), + Animation.ABSOLUTE, 0, + Animation.ABSOLUTE, 0); + + scaleAnimation.setDuration(animatedTransitionDuration); + scaleAnimation.setStartOffset(0); + scaleAnimation.setFillAfter(true); + scaleAndMove.addAnimation(scaleAnimation); + } + + // Set animation to the tile + currentTile.setAnimation(scaleAndMove); + } + // Add to the total animation set + animationSet.addAnimation(scaleAndMove); + } + + if (animationSet.getAnimations().size() > 0) { + Log.d(TAG, "Starting animation"); + animationSet.setFillAfter(true); + animationSet.start(); + } + } + + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java new file mode 100644 index 000000000..76a13d73b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java @@ -0,0 +1,157 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.LinkedList; +import java.util.List; + +/** + * Describes the positioning of a tiles in a 100x100 environment + */ +public class TilesLayoutPreset { + + // ========================================= + // Private Members + // ========================================= + + private List _positions; + private String _presetName; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayoutPreset(String name) { + _presetName = name; + _positions = new LinkedList(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void add(float x, float y, float width, float height) { + TilePosition tilePosition = new TilePosition(x, y, height, width); + add(tilePosition); + } + + public void add(TilePosition tilePosition) { + _positions.add(tilePosition); + } + + public Iterable getTilePositions() { + return _positions; + } + + public int getCount() { + return _positions.size(); + } + + // ========================================= + // Static Presets Factories + // ========================================= + + public static TilesLayoutPreset get1x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X1"); + preset.add(0, 0, 100, 100); + return preset; + } + + + public static TilesLayoutPreset get1x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X2"); + preset.add(0, 0, 50, 100); + preset.add(0, 50, 50, 100); + return preset; + } + + + public static TilesLayoutPreset get2x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X1"); + preset.add(0, 0, 100, 50); + preset.add(50, 0, 100, 50); + return preset; + } + + + public static TilesLayoutPreset get2x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + preset.add(50, 50, 50, 50); + return preset; + } + + public static TilesLayoutPreset get3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X3"); + preset.add(0, 0, 100/3f, 100/3f); + preset.add(100/3f, 0, 100/3f, 100/3f); + preset.add(200/3f, 0, 100/3f, 100/3f); + preset.add(0, 100/3f, 100/3f, 100/3f); + preset.add(100/3f, 100/3f, 100/3f, 100/3f); + preset.add(200/3f, 100/3f, 100/3f, 100/3f); + preset.add(0, 200/3f, 100/3f, 100/3f); + preset.add(100/3f, 200/3f, 100/3f, 100/3f); + preset.add(200/3f, 200/3f, 100/3f, 100/3f); + return preset; + } + + public static TilesLayoutPreset get3x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X2"); + preset.add(0, 0, 50, 100/3f); + preset.add(100/3f, 0, 50, 100/3f); + preset.add(200/3f, 0, 50, 100/3f); + preset.add(0, 50, 50, 100/3f); + preset.add(100/3f, 50, 50, 100/3f); + preset.add(200/3f, 50, 50, 100/3f); + return preset; + } + + public static TilesLayoutPreset get2x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X3"); + preset.add(0, 0, 100/3f, 50); + preset.add(50, 0, 100/3f, 50); + preset.add(0, 100/3f, 100/3f, 50); + preset.add(50, 100/3f, 100/3f, 50); + preset.add(0, 200/3f, 100/3f, 50); + preset.add(50, 200/3f, 100/3f, 50); + return preset; + } + + + public static TilesLayoutPreset get4x4() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 25, 25); + preset.add(25, 0, 25, 25); + preset.add(50, 0, 25, 25); + preset.add(75, 0, 25, 25); + preset.add(0, 25, 25, 25); + preset.add(25, 25, 25, 25); + preset.add(50, 25, 25, 25); + preset.add(75, 25, 25, 25); + preset.add(0, 50, 25, 25); + preset.add(25, 50, 25, 25); + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(0, 75, 25, 25); + preset.add(25, 75, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + return preset; + } + + public static TilesLayoutPreset get2x3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Custom 2X4X4"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + + return preset; + } + + +} From c3b5f90b506e8cc14fadf9a914306b732011f4f8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:02:05 -0500 Subject: [PATCH 260/508] AndroidGCS: Refactor the UAVO browser to use a split view - objects names on the side and content on the other side. Add a filter for settings versus data. --- androidgcs/res/layout/object_browser.xml | 54 +++++++++++- androidgcs/res/layout/pfd.xml | 34 ++++++-- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++------ .../src/org/openpilot/uavtalk/UAVObject.java | 9 +- .../org/openpilot/uavtalk/UAVObjectField.java | 6 +- 5 files changed, 151 insertions(+), 36 deletions(-) diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 9c7456915..67dc0af76 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,6 +2,56 @@ - - + + + + + + + + + + + + + + + + + + + + + + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml index 191a80eb9..5291f2724 100644 --- a/androidgcs/res/layout/pfd.xml +++ b/androidgcs/res/layout/pfd.xml @@ -1,8 +1,30 @@ - - - + + + + + + + + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a6ed177a2..1a7495ada 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -16,8 +16,12 @@ import android.util.Log; import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; +import android.widget.CheckBox; +import android.widget.CompoundButton; +import android.widget.CompoundButton.OnCheckedChangeListener; import android.widget.ListView; import android.widget.Spinner; +import android.widget.TextView; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -27,6 +31,7 @@ import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; + int selected_index = -1; boolean connected; SharedPreferences prefs; ArrayAdapter adapter; @@ -35,10 +40,15 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - Log.d(TAG,"Update"); - update(); + updateObject(); } }; + + private final Observer updatedObserver = new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }; /** Called when the activity is first created. */ @Override @@ -47,20 +57,48 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); - - Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + + OnCheckedChangeListener checkListener = new OnCheckedChangeListener() { + @Override + public void onCheckedChanged(CompoundButton buttonView, + boolean isChecked) { + updateList(); + } + }; + + ((CheckBox) findViewById(R.id.dataCheck)).setOnCheckedChangeListener(checkListener); + ((CheckBox) findViewById(R.id.settingsCheck)).setOnCheckedChangeListener(checkListener); + + updateList(); + } + + /** + * Populate the list of UAVO objects based on the selected filter + */ + private void updateList() { + // Disconnect any previous signals + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + selected_index = -1; + + boolean includeData = ((CheckBox) findViewById(R.id.dataCheck)).isChecked(); + boolean includeSettings = ((CheckBox) findViewById(R.id.settingsCheck)).isChecked(); List> allobjects = objMngr.getDataObjects(); allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - allObjects.addAll(li.next()); + List objects = li.next(); + if(includeSettings && objects.get(0).isSettings()) + allObjects.addAll(objects); + else if (includeData && !objects.get(0).isSettings()) + allObjects.addAll(objects); } adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); @@ -70,29 +108,25 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref objects.setOnItemClickListener(new OnItemClickListener() { public void onItemClick(AdapterView parent, View view, int position, long id) { - /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), - Toast.LENGTH_SHORT).show();*/ - Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); - intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); - intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); - intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); - startActivity(intent); + + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + + selected_index = position; + allObjects.get(position).addUpdatedObserver(updatedObserver); + updateObject(); } }); - - - UAVObject obj = objMngr.getObject("SystemStats"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - + } - - public void update() { - adapter.notifyDataSetChanged(); + + private void updateObject() { + //adapter.notifyDataSetChanged(); + TextView text = (TextView) findViewById(R.id.object_information); + if (selected_index >= 0 && selected_index < allObjects.size()) + text.setText(allObjects.get(selected_index).toStringData()); + else + Log.d(TAG,"Update called but invalid index: " + selected_index); } public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 28c279040..087d2b808 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -52,6 +52,11 @@ public abstract class UAVObject { } private CallbackListener updatedListeners = new CallbackListener(this); + public void removeUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.deleteObserver(o); + } + } public void addUpdatedObserver(Observer o) { synchronized(updatedListeners) { updatedListeners.addObserver(o); @@ -730,14 +735,14 @@ public abstract class UAVObject { */ @Override public String toString() { - return toStringBrief() + toStringData(); + return toStringBrief(); // + toStringData(); } /** * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName(); // + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 3ed221079..af707d3a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,11 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + data.toString() + " (" + units + ")\n"; + sout += name + ": " + getValue().toString(); + if (units.length() > 0) + sout += " (" + units + ")\n"; + else + sout += "\n"; return sout; } From ad496ab8a35b206c67f23ae87d8d22f4f50efa4b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 22:20:00 -0500 Subject: [PATCH 261/508] AndroidGCS: Output all fields from the UAVObjects --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index af707d3a0..988642ff0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,14 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + getValue().toString(); + sout += name + ": "; + for (int i = 0; i < numElements; i++) { + sout += getValue(i).toString(); + if (i != numElements-1) + sout += ", "; + else + sout += " "; + } if (units.length() > 0) sout += " (" + units + ")\n"; else From 7fe8e314a78b44ab195001ad5bc79cceb01d3575 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 23:00:25 -0500 Subject: [PATCH 262/508] AndroidGCS: Refine the graphics of the object editor --- androidgcs/AndroidManifest.xml | 4 +- androidgcs/res/layout/object_browser.xml | 71 ++++++++--- androidgcs/res/layout/object_edit.xml | 9 -- androidgcs/res/layout/object_editor.xml | 49 +++++++- .../openpilot/androidgcs/ObjectBrowser.java | 19 ++- .../openpilot/androidgcs/ObjectEditView.java | 117 ++++++++---------- .../openpilot/androidgcs/ObjectEditor.java | 18 ++- 7 files changed, 179 insertions(+), 108 deletions(-) delete mode 100644 androidgcs/res/layout/object_edit.xml diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 40b08c328..52bf9cb30 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,14 +2,14 @@ - + - + diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 67dc0af76..567c04f15 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -1,10 +1,13 @@ - + - + + + - - - + android:drawSelectorOnTop="true" + android:choiceMode="singleChoice"/> + + + + + + + + + + + - - diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml index d93b1a097..be6e219e8 100644 --- a/androidgcs/res/layout/object_editor.xml +++ b/androidgcs/res/layout/object_editor.xml @@ -1,6 +1,45 @@ - - + + + + + + + + + + + + + + + android:layout_column="1" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_map" + android:text="@string/location_name" /> + android:layout_column="2" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_pfd" + android:text="@string/pfd_name" /> - \ No newline at end of file +
From f37433e28013b04758c8b48059a7539c70a275a6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 23 Aug 2012 09:26:07 -0500 Subject: [PATCH 372/508] AndroidGCS OSG: Force inclusion of the 3DS plugin and use a 3DS model. Also include the jpeg and png libraries and plugins to load the textures. However they currently aren't visible. --- androidgcs/jni/Android.mk | 4 +++- androidgcs/jni/OsgMainApp.hpp | 4 ++++ androidgcs/src/org/openpilot/androidgcs/OsgViewer.java | 2 +- 3 files changed, 8 insertions(+), 2 deletions(-) diff --git a/androidgcs/jni/Android.mk b/androidgcs/jni/Android.mk index 1379684c9..6d45d27b1 100644 --- a/androidgcs/jni/Android.mk +++ b/androidgcs/jni/Android.mk @@ -18,7 +18,7 @@ LOCAL_C_INCLUDES:= $(OSG_ANDROID_DIR)/include LOCAL_CFLAGS := -Werror -fno-short-enums LOCAL_CPPFLAGS := -DOSG_LIBRARY_STATIC -LOCAL_LDLIBS := -llog -lGLESv2 -ldl -lz -lgnustl_static +LOCAL_LDLIBS := -llog -lGLESv2 -ldl -lz -lgnustl_static -ljpeg -lpng LOCAL_SRC_FILES := osgNativeLib.cpp OsgMainApp.cpp OsgAndroidNotifyHandler.cpp LOCAL_LDFLAGS := -L $(LIBDIR) \ -losgdb_dds \ @@ -29,6 +29,8 @@ LOCAL_LDFLAGS := -L $(LIBDIR) \ -losgdb_osg \ -losgdb_ive \ -losgdb_3ds \ +-losgdb_jpeg \ +-losgdb_png \ -losgdb_deprecated_osgviewer \ -losgdb_deprecated_osgvolume \ -losgdb_deprecated_osgtext \ diff --git a/androidgcs/jni/OsgMainApp.hpp b/androidgcs/jni/OsgMainApp.hpp index a1a974659..5f9ef0ab1 100644 --- a/androidgcs/jni/OsgMainApp.hpp +++ b/androidgcs/jni/OsgMainApp.hpp @@ -59,6 +59,10 @@ USE_OSGPLUGIN(terrain) USE_OSGPLUGIN(rgb) USE_OSGPLUGIN(OpenFlight) USE_OSGPLUGIN(dds) +USE_OSGPLUGIN(3ds) +USE_OSGPLUGIN(jpeg) +USE_OSGPLUGIN(png) + //Static DOTOSG USE_DOTOSGWRAPPER_LIBRARY(osg) USE_DOTOSGWRAPPER_LIBRARY(osgFX) diff --git a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java index 95db9619f..9928b19cf 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java +++ b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java @@ -85,7 +85,7 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList msgUiLightOn = Toast.makeText(getApplicationContext(), "toast3", Toast.LENGTH_SHORT); msgUiLightOff = Toast.makeText(getApplicationContext(), "toast4", Toast.LENGTH_SHORT); - String address = Environment.getExternalStorageDirectory().getPath() + "/Models/quad.osg"; + String address = Environment.getExternalStorageDirectory().getPath() + "/Models/J14-QT_X.3DS"; //quad.osg"; Log.d(TAG, "Address: " + address); osgNativeLib.loadObject(address); } From 7ce0004c470c48025cc55be06aea0ee984dd104e Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 24 Aug 2012 19:25:02 -0700 Subject: [PATCH 373/508] Added include of stdint.h to aes.c --- flight/Libraries/aes.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Libraries/aes.c b/flight/Libraries/aes.c index d381f157a..c21ce2f9e 100644 --- a/flight/Libraries/aes.c +++ b/flight/Libraries/aes.c @@ -1,7 +1,7 @@ // http://gladman.plushost.co.uk/oldsite/AES/index.php -//#include +#include #include "aes.h" From 34b433e074fd831f31ff903bde3f6bafc1d59064 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 24 Aug 2012 19:42:10 -0700 Subject: [PATCH 374/508] Added UAVTalkSendBuf function and added locking in UAVTalkSendAck and UAVTalkSendNack. --- flight/UAVTalk/inc/uavtalk.h | 1 + flight/UAVTalk/uavtalk.c | 52 ++++++++++++++++++++++++++++++++++-- 2 files changed, 51 insertions(+), 2 deletions(-) diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index ab47a1924..f7fc58cd1 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -56,6 +56,7 @@ int32_t UAVTalkSendObjectTimestamped(UAVTalkConnection connectionHandle, UAVObjH int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId); int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId); +int32_t UAVTalkSendBuf(UAVTalkConnection connectionHandle, uint8_t *buf, uint16_t len); UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte); void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 98a2081ac..b2f8515c8 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -570,7 +570,15 @@ int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uin UAVTalkConnectionData *connection; CHECKCONHANDLE(connectionHandle,connection,return -1); - return sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + int32_t ret = sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); + + // Release lock + xSemaphoreGiveRecursive(connection->lock); + + return ret; } /** @@ -585,7 +593,47 @@ int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId) UAVTalkConnectionData *connection; CHECKCONHANDLE(connectionHandle,connection,return -1); - return sendNack(connection, objId); + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + int32_t ret = sendNack(connection, objId); + + // Release lock + xSemaphoreGiveRecursive(connection->lock); + + return ret; +} + +/** + * Send a buffer containing a UAVTalk message through the telemetry link. + * This function locks the connection prior to sending. + * \param[in] connection UAVTalkConnection to be used + * \param[in] buf The data buffer containing the UAVTalk message + * \param[in] len The number of bytes to send from the data buffer + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSendBuf(UAVTalkConnection connectionHandle, uint8_t *buf, uint16_t len) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection, return -1); + + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + // Output the buffer + int32_t rc = (*connection->outStream)(buf, len); + + // Update stats + connection->stats.txBytes += len; + + // Release lock + xSemaphoreGiveRecursive(connection->lock); + + // Done + if (rc != len) + return -1; + return 0; } /** From 789746151ab2985d7feb169923070377c54a0a4b Mon Sep 17 00:00:00 2001 From: a*morale Date: Sat, 25 Aug 2012 11:29:01 +0200 Subject: [PATCH 375/508] Fixes the selection of the oversample settings from the pios_ms5611_cfg.oversapling configuration --- flight/PiOS/Common/pios_ms5611.c | 7 +++---- flight/Revolution/System/pios_board.c | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/flight/PiOS/Common/pios_ms5611.c b/flight/PiOS/Common/pios_ms5611.c index 1d06f1dea..41bf7c80e 100644 --- a/flight/PiOS/Common/pios_ms5611.c +++ b/flight/PiOS/Common/pios_ms5611.c @@ -56,7 +56,6 @@ static uint32_t oversampling; static const struct pios_ms5611_cfg * dev_cfg; static int32_t i2c_id; -static enum pios_ms5611_osr osr = MS5611_OSR_256; /** * Initialise the MS5611 sensor @@ -90,10 +89,10 @@ int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type) { /* Start the conversion */ if (Type == TemperatureConv) { - while (PIOS_MS5611_WriteCommand(MS5611_TEMP_ADDR + osr) != 0) + while (PIOS_MS5611_WriteCommand(MS5611_TEMP_ADDR + oversampling) != 0) continue; } else if (Type == PressureConv) { - while (PIOS_MS5611_WriteCommand(MS5611_PRES_ADDR + osr) != 0) + while (PIOS_MS5611_WriteCommand(MS5611_PRES_ADDR + oversampling) != 0) continue; } @@ -106,7 +105,7 @@ int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type) * @brief Return the delay for the current osr */ int32_t PIOS_MS5611_GetDelay() { - switch(osr) { + switch(oversampling) { case MS5611_OSR_256: return 2; case MS5611_OSR_512: diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index b9360bfef..b098f3cd0 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -131,7 +131,7 @@ static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { #if defined(PIOS_INCLUDE_MS5611) #include "pios_ms5611.h" static const struct pios_ms5611_cfg pios_ms5611_cfg = { - .oversampling = 1, + .oversampling = MS5611_OSR_512, }; #endif /* PIOS_INCLUDE_MS5611 */ From 257b00a400de345c69b0df823ddf31974b85694b Mon Sep 17 00:00:00 2001 From: a*morale Date: Sat, 25 Aug 2012 12:28:25 +0200 Subject: [PATCH 376/508] Fixed a typo on I2C speed for the MS5611 --- flight/board_hw_defs/revolution/board_hw_defs.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index b54dd119d..2bc703cd8 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -1224,7 +1224,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = { .I2C_Ack = I2C_Ack_Enable, .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 40000, /* bits/s */ + .I2C_ClockSpeed = 400000, /* bits/s */ }, .transfer_timeout_ms = 50, .scl = { From c696cccff8507c58c060089d231317e2fd931659 Mon Sep 17 00:00:00 2001 From: a*morale Date: Sat, 25 Aug 2012 13:04:41 +0200 Subject: [PATCH 377/508] Added an option to be able to change the interleave between Pressure and Temperature conversion for the MS5611 To enable this option define the PIOS_MS5611_SLOW_TEMP_RATE with the number of Pressure conversion for each Temperature conversion. --- flight/Modules/Altitude/revolution/altitude.c | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Altitude/revolution/altitude.c b/flight/Modules/Altitude/revolution/altitude.c index 7f9052038..54b241408 100644 --- a/flight/Modules/Altitude/revolution/altitude.c +++ b/flight/Modules/Altitude/revolution/altitude.c @@ -100,6 +100,13 @@ static void altitudeTask(void *parameters) // TODO: Check the pressure sensor and set a warning if it fails test +// Option to change the interleave between Temp and Pressure conversions +// Undef for normal operation +//#define PIOS_MS5611_SLOW_TEMP_RATE 20 + +#ifdef PIOS_MS5611_SLOW_TEMP_RATE + uint8_t temp_press_interleave_count = 1; +#endif // Main task loop while (1) { @@ -128,11 +135,20 @@ static void altitudeTask(void *parameters) } #endif float temp, press; - +#ifdef PIOS_MS5611_SLOW_TEMP_RATE + temp_press_interleave_count --; + if(temp_press_interleave_count == 0) + { +#endif // Update the temperature data PIOS_MS5611_StartADC(TemperatureConv); vTaskDelay(PIOS_MS5611_GetDelay()); PIOS_MS5611_ReadADC(); + +#ifdef PIOS_MS5611_SLOW_TEMP_RATE + temp_press_interleave_count=PIOS_MS5611_SLOW_TEMP_RATE; + } +#endif // Update the pressure data PIOS_MS5611_StartADC(PressureConv); From 60160001c69d8435466fb9ac1c0df8e294a8ef29 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 12:23:54 -0500 Subject: [PATCH 378/508] Copy the revo project to revo mini --- flight/Bootloaders/RevoMini/Makefile | 383 ++++ flight/Bootloaders/RevoMini/inc/common.h | 115 ++ flight/Bootloaders/RevoMini/inc/op_dfu.h | 60 + flight/Bootloaders/RevoMini/inc/pios_config.h | 43 + .../RevoMini/inc/pios_usb_board_data.h | 52 + flight/Bootloaders/RevoMini/main.c | 230 +++ flight/Bootloaders/RevoMini/op_dfu.c | 468 +++++ flight/Bootloaders/RevoMini/pios_board.c | 78 + .../RevoMini/pios_usb_board_data.c | 98 + flight/RevoMini/Makefile | 495 +++++ flight/RevoMini/Makefile.osx | 669 ++++++ flight/RevoMini/System/alarms.c | 210 ++ flight/RevoMini/System/cm3_fault_handlers.c | 87 + flight/RevoMini/System/dcc_stdio.c | 149 ++ flight/RevoMini/System/inc/FreeRTOSConfig.h | 103 + flight/RevoMini/System/inc/alarms.h | 50 + flight/RevoMini/System/inc/dcc_stdio.h | 36 + flight/RevoMini/System/inc/op_config.h | 39 + flight/RevoMini/System/inc/openpilot.h | 53 + flight/RevoMini/System/inc/pios_board_sim.h | 85 + flight/RevoMini/System/inc/pios_config.h | 122 ++ flight/RevoMini/System/inc/pios_config_sim.h | 79 + .../RevoMini/System/inc/pios_usb_board_data.h | 46 + flight/RevoMini/System/pios_board.c | 885 ++++++++ flight/RevoMini/System/pios_board_sim.c | 229 +++ flight/RevoMini/System/pios_usb_board_data.c | 98 + flight/RevoMini/System/revolution.c | 142 ++ flight/RevoMini/UAVObjects.inc | 96 + flight/board_hw_defs/revomini/board_hw_defs.c | 1823 +++++++++++++++++ 29 files changed, 7023 insertions(+) create mode 100644 flight/Bootloaders/RevoMini/Makefile create mode 100644 flight/Bootloaders/RevoMini/inc/common.h create mode 100644 flight/Bootloaders/RevoMini/inc/op_dfu.h create mode 100644 flight/Bootloaders/RevoMini/inc/pios_config.h create mode 100644 flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h create mode 100644 flight/Bootloaders/RevoMini/main.c create mode 100644 flight/Bootloaders/RevoMini/op_dfu.c create mode 100644 flight/Bootloaders/RevoMini/pios_board.c create mode 100644 flight/Bootloaders/RevoMini/pios_usb_board_data.c create mode 100644 flight/RevoMini/Makefile create mode 100644 flight/RevoMini/Makefile.osx create mode 100644 flight/RevoMini/System/alarms.c create mode 100644 flight/RevoMini/System/cm3_fault_handlers.c create mode 100644 flight/RevoMini/System/dcc_stdio.c create mode 100644 flight/RevoMini/System/inc/FreeRTOSConfig.h create mode 100644 flight/RevoMini/System/inc/alarms.h create mode 100644 flight/RevoMini/System/inc/dcc_stdio.h create mode 100644 flight/RevoMini/System/inc/op_config.h create mode 100644 flight/RevoMini/System/inc/openpilot.h create mode 100644 flight/RevoMini/System/inc/pios_board_sim.h create mode 100644 flight/RevoMini/System/inc/pios_config.h create mode 100644 flight/RevoMini/System/inc/pios_config_sim.h create mode 100644 flight/RevoMini/System/inc/pios_usb_board_data.h create mode 100644 flight/RevoMini/System/pios_board.c create mode 100644 flight/RevoMini/System/pios_board_sim.c create mode 100644 flight/RevoMini/System/pios_usb_board_data.c create mode 100644 flight/RevoMini/System/revolution.c create mode 100644 flight/RevoMini/UAVObjects.inc create mode 100644 flight/board_hw_defs/revomini/board_hw_defs.c diff --git a/flight/Bootloaders/RevoMini/Makefile b/flight/Bootloaders/RevoMini/Makefile new file mode 100644 index 000000000..d708a6c82 --- /dev/null +++ b/flight/Bootloaders/RevoMini/Makefile @@ -0,0 +1,383 @@ + ##### + # Project: OpenPilot INS_BOOTLOADER + # + # + # Makefile for OpenPilot INS project + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +TOP := $(realpath $(WHEREAMI)/../../../) +include $(TOP)/make/firmware-defs.mk +include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk + +# Target file name (without extension). +TARGET := bl_$(BOARD_NAME) + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR := $(TOP)/build/$(TARGET) + +# Set developer code and compile options +# Set to YES for debugging +DEBUG ?= NO + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +ifeq ($(CODE_SOURCERY), YES) +REMOVE_CMD = cs-rm +else +REMOVE_CMD = rm +endif + +# Paths +REVO_BL = $(WHEREAMI) +REVO_BLINC = $(REVO_BL)/inc +PIOS = ../../PiOS +PIOSINC = $(PIOS)/inc +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = ../../Libraries/inc +PIOSSTM32F4XX = $(PIOS)/STM32F4xx +PIOSCOMMON = $(PIOS)/Common +PIOSBOARDS = $(PIOS)/Boards +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +APPLIBDIR = $(PIOSSTM32F4XX)/Libraries +STMLIBDIR = $(APPLIBDIR) +STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver +STMSPDSRCDIR = $(STMSPDDIR)/src +STMSPDINCDIR = $(STMSPDDIR)/inc +HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +## BOOTLOADER: +SRC += main.c +SRC += pios_board.c +SRC += pios_usb_board_data.c +SRC += op_dfu.c + +## PIOS Hardware (STM32F4xx) +include $(PIOS)/STM32F4xx/library.mk + +# PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_board_info.c +SRC += $(PIOSCOMMON)/pios_com_msg.c +SRC += $(PIOSCOMMON)/printf-stdarg.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSSTM34FXX) +EXTRAINCDIRS += $(PIOSCOMMON) +EXTRAINCDIRS += $(PIOSBOARDS) +EXTRAINCDIRS += $(STMSPDINCDIR) +EXTRAINCDIRS += $(CMSISDIR) +EXTRAINCDIRS += $(REVO_BLINC) +EXTRAINCDIRS += $(HWDEFSINC) + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32FXX) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +CDEFS = -DSTM32F4XX +CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +CDEFS += -DUSE_STDPERIPH_DRIVER +CDEFS += -DUSE_$(BOARD) + +# Provide (only) the bootloader with board-specific defines +BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) +BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) +BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) +BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) +BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) + +# Place project-specific -D and/or -U options for +# Assembler with preprocessor here. +#ADEFS = -DUSE_IRQ_ASM_WRAPPER +ADEFS = -D__ASSEMBLY__ + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS = +endif + +# This is not the best place for these. Really should abstract out +# to the board file or something +CFLAGS += -DSTM32F4XX +CFLAGS += -DMEM_SIZE=1024000000 + +CFLAGS += -g$(DEBUGF) +CFLAGS += -O$(OPT) +ifeq ($(DEBUG),NO) +CFLAGS += -fdata-sections -ffunction-sections +endif +CFLAGS += -mcpu=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(BLONLY_CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +CFLAGS += -mapcs-frame +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +#CFLAGS += -Werror +CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections +ifeq ($(DEBUG),NO) +LDFLAGS += -Wl,-static +endif +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +#Linker scripts +LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_BL)) + +# Define programs and commands. +REMOVE = $(REMOVE_CMD) -f + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +# Default target. +all: build + +ifeq ($(LOADFORMAT),ihex) +build: elf hex sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Link: create ELF output file from object files. +$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) + +# Assemble: create object files from assembler source files. +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + +# Compile: create assembler files from C source files. ARM/Thumb +$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) + +# Compile: create assembler files from C source files. ARM only +$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) + +$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin + +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) + +# Add jtag targets (program and wipe) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) + +.PHONY: elf lss sym hex bin bino +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin +bino: $(OUTDIR)/$(TARGET).bin.o + +# Display sizes of sections. +$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + +# Target: clean project. +clean: clean_list + +clean_list : + @echo $(MSG_CLEANING) + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o + $(V1) $(REMOVE) $(ALLOBJ) + $(V1) $(REMOVE) $(LSTFILES) + $(V1) $(REMOVE) $(DEPFILES) + $(V1) $(REMOVE) $(SRC:.c=.s) + $(V1) $(REMOVE) $(SRCARM:.c=.s) + $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) + $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL) +else +$(shell mkdir -p $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir -p $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + +# Listing of phony targets. +.PHONY : all build clean clean_list install diff --git a/flight/Bootloaders/RevoMini/inc/common.h b/flight/Bootloaders/RevoMini/inc/common.h new file mode 100644 index 000000000..9ecff4079 --- /dev/null +++ b/flight/Bootloaders/RevoMini/inc/common.h @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/Bootloaders/RevoMini/inc/op_dfu.h b/flight/Bootloaders/RevoMini/inc/op_dfu.h new file mode 100644 index 000000000..e031c3364 --- /dev/null +++ b/flight/Bootloaders/RevoMini/inc/op_dfu.h @@ -0,0 +1,60 @@ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/Bootloaders/RevoMini/inc/pios_config.h b/flight/Bootloaders/RevoMini/inc/pios_config.h new file mode 100644 index 000000000..cfe34aaad --- /dev/null +++ b/flight/Bootloaders/RevoMini/inc/pios_config.h @@ -0,0 +1,43 @@ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * - Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_COM_MSG +#define PIOS_INCLUDE_BL_HELPER +#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT + +#endif /* PIOS_CONFIG_H */ diff --git a/flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h b/flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h new file mode 100644 index 000000000..ac75b8cfa --- /dev/null +++ b/flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h @@ -0,0 +1,52 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 2 + +#include "pios_usb_defs.h" /* struct usb_* */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_BL) +#define PIOS_USB_BOARD_SN_SUFFIX "+BL" + +/* + * The bootloader uses a simplified report structure + * BL: ... + * FW: ... + * This define changes the behaviour in pios_usb_hid.c + */ +#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/Bootloaders/RevoMini/main.c b/flight/Bootloaders/RevoMini/main.c new file mode 100644 index 000000000..6fb4fd8e6 --- /dev/null +++ b/flight/Bootloaders/RevoMini/main.c @@ -0,0 +1,230 @@ +/** + ****************************************************************************** + * @addtogroup RevolutionBL Revolution BootLoader + * @brief These files contain the code to the Revolution Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the Revolution BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include +#include "op_dfu.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +void check_bor(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +bool JumpToApp = false; +bool GO_dfu = false; +bool USB_connected = false; +bool User_DFU_request = false; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + // Make sure the brown out reset value for this chip + // is 2.7 volts + check_bor(); + + USB_connected = PIOS_USB_CheckAvailable(0); + + if (PIOS_IAP_CheckRequest() == true) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = true; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == true) || (User_DFU_request == true); + + if (GO_dfu == true) { + if (User_DFU_request == true) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = true; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (true) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == true) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = true; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_LED_On(PIOS_LED_HEARTBEAT); + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + + PIOS_USBHOOK_Deactivate(); + + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return true; +} + +/** + * Check the brown out reset threshold is 2.7 volts and if not + * resets it. This solves an issue that can prevent boards + * powering up with some BEC + */ +void check_bor() +{ + uint8_t bor = FLASH_OB_GetBOR(); + if(bor != OB_BOR_LEVEL3) { + FLASH_OB_Unlock(); + FLASH_OB_BORConfig(OB_BOR_LEVEL3); + FLASH_OB_Launch(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + FLASH_OB_Lock(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + } +} + diff --git a/flight/Bootloaders/RevoMini/op_dfu.c b/flight/Bootloaders/RevoMini/op_dfu.c new file mode 100644 index 000000000..3aceedcfb --- /dev/null +++ b/flight/Bootloaders/RevoMini/op_dfu.c @@ -0,0 +1,468 @@ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, xReceive_Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(true); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = true; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == true) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = false; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = false; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(true); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 + + downSizeOfLastPacket * 4) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[0] = echoBuffer[0] | (1 << 6); + sendData(echoBuffer, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return true; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return false; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return true; + break; + default: + return false; + } +} diff --git a/flight/Bootloaders/RevoMini/pios_board.c b/flight/Bootloaders/RevoMini/pios_board.c new file mode 100644 index 000000000..143124ade --- /dev/null +++ b/flight/Bootloaders/RevoMini/pios_board.c @@ -0,0 +1,78 @@ +/** + ****************************************************************************** + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board specific static initializers for hardware for the AHRS board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Pull in the board-specific static HW definitions. + * Including .c files is a bit ugly but this allows all of + * the HW definitions to be const and static to limit their + * scope. + * + * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE + */ +#include "board_hw_defs.c" + +#include +#include + +uint32_t pios_com_telem_usb_id; + +static bool board_init_complete = false; +void PIOS_Board_Init() { + if (board_init_complete) { + return; + } + + /* Delay system */ + PIOS_DELAY_Init(); + +#if defined(PIOS_INCLUDE_LED) + PIOS_LED_Init(&pios_led_cfg); +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Activate the HID-only USB configuration */ + PIOS_USB_DESC_HID_ONLY_Init(); + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { + PIOS_Assert(0); + } +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ + + PIOS_USBHOOK_Activate(); + +#endif /* PIOS_INCLUDE_USB */ + + board_init_complete = true; +} diff --git a/flight/Bootloaders/RevoMini/pios_usb_board_data.c b/flight/Bootloaders/RevoMini/pios_usb_board_data.c new file mode 100644 index 000000000..0fb67116d --- /dev/null +++ b/flight/Bootloaders/RevoMini/pios_usb_board_data.c @@ -0,0 +1,98 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ + +static const uint8_t usb_product_id[22] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'R', 0, + 'e', 0, + 'v', 0, + 'o', 0, + 'l', 0, + 'u', 0, + 't', 0, + 'i', 0, + 'o', 0, + 'n', 0, +}; + +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_US), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; + PIOS_SYS_SerialNumberGet((char *)sn); + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile new file mode 100644 index 000000000..88d154ba5 --- /dev/null +++ b/flight/RevoMini/Makefile @@ -0,0 +1,495 @@ +##### +# Project: OpenPilot INS +# +# +# Makefile for OpenPilot INS project +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. +# +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### + +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +TOP := $(realpath $(WHEREAMI)/../../) +include $(TOP)/make/firmware-defs.mk +include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk + +# Target file name (without extension). +TARGET := fw_$(BOARD_NAME) + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR := $(TOP)/build/$(TARGET) + +# Set developer code and compile options +# Set to YES for debugging +DEBUG ?= NO + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +ifeq ($(CODE_SOURCERY), YES) +REMOVE_CMD = cs-rm +else +REMOVE_CMD = rm +endif + +FLASH_TOOL = OPENOCD + +# List of modules to include +MODULES = Sensors Attitude/revolution ManualControl Stabilization Actuator +MODULES += Battery +MODULES += Altitude/revolution GPS FirmwareIAP +MODULES += Airspeed/revolution +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +MODULES += CameraStab +MODULES += OveroSync +MODULES += Telemetry +PYMODULES = +#FlightPlan + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +PIOS = ../PiOS +PIOSINC = $(PIOS)/inc +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = ../Libraries/inc +PIOSSTM32F4XX = $(PIOS)/STM32F4xx +PIOSCOMMON = $(PIOS)/Common +PIOSBOARDS = $(PIOS)/Boards +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +APPLIBDIR = $(PIOSSTM32F4XX)/Libraries +STMLIBDIR = $(APPLIBDIR) +STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver +STMSPDSRCDIR = $(STMSPDDIR)/src +STMSPDINCDIR = $(STMSPDDIR)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +BOOT = ../Bootloaders/INS +BOOTINC = $(BOOT)/inc +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans +HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight + +SRC = +# optional component libraries +include $(PIOSCOMMONLIB)/FreeRTOS/library.mk +#include $(PIOSCOMMONLIB)/dosfs/library.mk +include $(PIOSCOMMONLIB)/msheap/library.mk + + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +## PyMite files and modules +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +PYSRC += $(wildcard ${PYMITEVM}/*.c) +PYSRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += $(PYSRC) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c + +#ifeq ($(DEBUG),YES) +SRC += $(OPSYSTEM)/dcc_stdio.c +SRC += $(OPSYSTEM)/cm3_fault_handlers.c +#endif + +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c + +## PIOS Hardware (STM32F4xx) +include $(PIOS)/STM32F4xx/library.mk + +## PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_mpu6000.c +SRC += $(PIOSCOMMON)/pios_bma180.c +SRC += $(PIOSCOMMON)/pios_etasv3.c +SRC += $(PIOSCOMMON)/pios_gcsrcvr.c +SRC += $(PIOSCOMMON)/pios_l3gd20.c +SRC += $(PIOSCOMMON)/pios_hmc5883.c +SRC += $(PIOSCOMMON)/pios_ms5611.c +SRC += $(PIOSCOMMON)/pios_crc.c +SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_flash_jedec.c +SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c +SRC += $(PIOSCOMMON)/printf-stdarg.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c +SRC += $(PIOSCOMMON)/pios_usb_util.c + +include ./UAVObjects.inc +SRC += $(UAVOBJSRC) + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + +# List Assembler source files here. +# Make them always end in a capital .S. Files ending in a lowercase .s +# will not be considered source files but generated files (assembler +# output from the compiler), and will be deleted upon "make clean"! +# Even though the DOS/Win* filesystem matches both .s and .S the same, +# it will preserve the spelling of the filenames, and gcc itself does +# care about how the name is spelled on its command-line. + + +# List Assembler source files here which must be assembled in ARM-Mode.. +ASRCARM = + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSSTM32F4XX) +EXTRAINCDIRS += $(PIOSCOMMON) +EXTRAINCDIRS += $(PIOSBOARDS) +EXTRAINCDIRS += $(STMSPDINCDIR) +EXTRAINCDIRS += $(CMSISDIR) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) +EXTRAINCDIRS += $(BOOTINC) +EXTRAINCDIRS += $(PYMITEINC) +EXTRAINCDIRS += $(HWDEFSINC) + +# Generate intermediate code +gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +$(PYSRC): gencode + +PYTHON = python + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) + @echo $(MSG_PYMITEINIT) $(call toprel, $@) + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py +EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F4XX) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +CFLAGS += -O0 +CFLAGS += -DGENERAL_COV +CFLAGS += -finstrument-functions -ffixed-r10 +else +CFLAGS += -Os +endif + + + +# common architecture-specific flags from the device-specific library makefile +CFLAGS += $(ARCHFLAGS) + +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +# This is not the best place for these. Really should abstract out +# to the board file or something +CFLAGS += -DSTM32F4XX +CFLAGS += -DMEM_SIZE=1024000000 + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) +CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) +CDEFS += -DUSE_STDPERIPH_DRIVER +CDEFS += -DUSE_$(BOARD) + +# Place project-specific -D and/or -U options for +# Assembler with preprocessor here. +#ADEFS = -DUSE_IRQ_ASM_WRAPPER +ADEFS = -D__ASSEMBLY__ + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +CFLAGS += -g$(DEBUGF) + +CFLAGS += -ffast-math + +CFLAGS += -mcpu=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +CFLAGS += -mapcs-frame +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +#CFLAGS += -Werror +CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = $(ARCHFLAGS) -mthumb -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +#Linker scripts +LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) + + +# Define programs and commands. +REMOVE = $(REMOVE_CMD) -f +PYHON = python + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +# Default target. +all: gccversion build + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + + +# Link: create ELF output file from object files. +$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) + +# Assemble: create object files from assembler source files. +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + +# Compile: create assembler files from C source files. ARM/Thumb +$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) + +# Compile: create assembler files from C source files. ARM only +$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) + +$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin + +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) + +# Add jtag targets (program and wipe) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) + +.PHONY: elf lss sym hex bin bino opfw +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin +bino: $(OUTDIR)/$(TARGET).bin.o +opfw: $(OUTDIR)/$(TARGET).opfw + +# Display sizes of sections. +$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).opfw +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).opfw +else + $(error INSTALL_DIR must be specified for $@) +endif + +# Target: clean project. +clean: clean_list + +clean_list : + @echo $(MSG_CLEANING) + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o + $(V1) $(REMOVE) $(ALLOBJ) + $(V1) $(REMOVE) $(LSTFILES) + $(V1) $(REMOVE) $(DEPFILES) + $(V1) $(REMOVE) $(SRC:.c=.s) + $(V1) $(REMOVE) $(SRCARM:.c=.s) + $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) + $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL) +else +$(shell mkdir -p $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + +# Listing of phony targets. +.PHONY : all build clean clean_list install diff --git a/flight/RevoMini/Makefile.osx b/flight/RevoMini/Makefile.osx new file mode 100644 index 000000000..c7db28918 --- /dev/null +++ b/flight/RevoMini/Makefile.osx @@ -0,0 +1,669 @@ + ##### + # Project: RevoMini + # + # + # Makefile for OpenPilot project build PiOS and the AP. + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + + +# Set developer code and compile options +# Set to YES to compile for debugging +DEBUG ?= YES + +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# +USE_BOOTLOADER ?= NO + + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +# Remove command is different for Code Sourcery on Windows +REMOVE_CMD ?= rm + +FLASH_TOOL = OPENOCD + +# YES enables -mthumb option to flags for source-files listed +# in SRC and CPPSRC +USE_THUMB_MODE = YES + +# List of modules to include +MODULES += Actuator ManualControl Stabilization +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +MODULES += Attitude/revolution +#MODULES += OveroSync/simulated + +# To run simulation instead of connect to SITL +MODULES += Sensors/simulated + +MODULES += Telemetry + +# MCU name, submodel and board +# - MCU used for compiler-option (-mtune) +# - MODEL used for linker-script name (-T) and passed as define +# - BOARD just passed as define (optional) +MCU = i686 +#CHIP = STM32F103RET +#BOARD = STM3210E_OP +MODEL = HD +ifeq ($(USE_BOOTLOADER), YES) +BOOT_MODEL = $(MODEL)_BL + +else +BOOT_MODEL = $(MODEL)_NB +endif + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR = ../../build/sim_osx + +# Target file name (without extension). +TARGET = RevoMini + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../PiOS.osx +PIOSINC = $(PIOS)/inc +PIOSPOSIX = $(PIOS)/osx +APPLIBDIR = $(PIOSPOSIX)/Libraries +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +MODNAMES = $(notdir ${MODULES}) + +ifndef TESTAPP + +## PyMite files +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +SRC += $(wildcard ${PYMITEVM}/*.c) +SRC += $(wildcard ${PYMITEPLAT}/*.c) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board_sim.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + + + +## UAVOBJECTS +ifndef TESTAPP +#include $(UAVOBJSYNTHDIR)/Makefile.inc +include ./UAVObjects.inc + +UAVOBJSRCFILENAMES += attitudesimulated +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + +SRC += $(UAVOBJSRC) +CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) +endif + +## PIOS Hardware (posix) +SRC += $(PIOSPOSIX)/pios_crc.c +SRC += $(PIOSPOSIX)/pios_sys.c +SRC += $(PIOSPOSIX)/pios_led.c +SRC += $(PIOSPOSIX)/pios_irq.c +SRC += $(PIOSPOSIX)/pios_delay.c +SRC += $(PIOSPOSIX)/pios_sdcard.c +SRC += $(PIOSPOSIX)/pios_udp.c +SRC += $(PIOSPOSIX)/pios_tcp.c +SRC += $(PIOSPOSIX)/pios_com.c +SRC += $(PIOSPOSIX)/pios_servo.c +SRC += $(PIOSPOSIX)/pios_wdg.c +SRC += $(PIOSPOSIX)/pios_debug.c + +SRC += $(PIOSPOSIX)/pios_rcvr.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c + +## RTOS and RTOS Portable +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +UNAME := $(shell uname) +SRC += $(RTOSSRCDIR)/task.c +SRC += $(RTOSSRCDIR)/timers.c +SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c + + + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSPOSIX) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix +EXTRAINCDIRS += $(PYMITEINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +#DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(USE_BOOTLOADER), YES) +CDEFS += -DUSE_BOOTLOADER +endif + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS = -g$(DEBUGF) -DDEBUG +endif + +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +CFLAGS += $(CFLAGS_UAVOBJECTS) +CFLAGS += -DARCH_POSIX +CFLAGS += -O$(OPT) +CFLAGS += -mtune=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +CFLAGS += -Werror +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS += -lpthread +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +# To include simulation model +LDFLAGS += -L$(OUTDIR) +#LDFLAGS += -lsimmodel + + +# Define programs and commands. +CC = $(TCHAIN_PREFIX)gcc +CPP = $(TCHAIN_PREFIX)g++ +AR = $(TCHAIN_PREFIX)ar +OBJCOPY = $(TCHAIN_PREFIX)objcopy +OBJDUMP = $(TCHAIN_PREFIX)objdump +SIZE = $(TCHAIN_PREFIX)size +NM = $(TCHAIN_PREFIX)nm +REMOVE = $(REMOVE_CMD) -f +PYTHON = python +###SHELL = sh +###COPY = cp + + + +# Define Messages +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} +MSG_END = ${quote}-------- end --------${quote} +MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} +MSG_SIZE_BEFORE = ${quote}Size before:${quote} +MSG_SIZE_AFTER = ${quote}Size after build:${quote} +MSG_LOAD_FILE = ${quote}Creating load file:${quote} +MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} +MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} +MSG_LINKING = ${quote}**** Linking :${quote} +MSG_COMPILING = ${quote}**** Compiling C :${quote} +MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} +MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} +MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} +MSG_ASSEMBLING = ${quote}**** Assembling:${quote} +MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} +MSG_CLEANING = ${quote}Cleaning project:${quote} +MSG_FORMATERROR = ${quote}Can not handle output-format${quote} +MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} +MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} +MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin + +# Default target. +#all: begin gccversion sizebefore build sizeafter finished end +#all: begin gencode gccversion build sizeafter finished end +all: elf + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Test if quotes are needed for the echo-command +result = ${shell echo "test"} +ifeq (${result}, test) + quote = ' +else + quote = +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +getmodname = $(firstword $(subst /, ,$1)) + +MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile.osx + echo ${MOD_GEN} + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @echo ${MSG_PYMITEINIT} + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py + +# Eye candy. +begin: +## @echo + @echo $(MSG_BEGIN) + +finished: +## @echo $(MSG_ERRORS_NONE) + +end: + @echo $(MSG_END) +## @echo + +# Display sizes of sections. +ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf +##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf +sizebefore: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi + +sizeafter: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi + @echo $(MSG_SIZE_AFTER) + $(ELFSIZE) + +# Display compiler version information. +gccversion : + @$(CC) --version +# @echo $(ALLOBJ) + +# Program the device. +ifeq ($(USE_BOOTLOADER), YES) +# Program the device with OP Upload Tool". +program: $(OUTDIR)/$(TARGET).bin + @echo ${quote}Programming with OP Upload Tool${quote} + ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin +else +ifeq ($(FLASH_TOOL),OPENOCD) +# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". +program: $(OUTDIR)/$(TARGET).elf + @echo ${quote}Programming with OPENOCD${quote} + $(OOCD_EXE) $(OOCD_CL) +endif +endif + +# Create final output file (.hex) from ELF output file. +%.hex: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O ihex $< $@ + +# Create final output file (.bin) from ELF output file. +%.bin: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O binary $< $@ + +# Create extended listing file/disassambly from ELF output file. +# using objdump testing: option -C +%.lss: %.elf +## @echo + @echo $(MSG_EXTENDED_LISTING) $@ + $(OBJDUMP) -h -S -C -r $< > $@ +# $(OBJDUMP) -x -S $< > $@ + +# Create a symbol table from ELF output file. +%.sym: %.elf +## @echo + @echo $(MSG_SYMBOL_TABLE) $@ + $(NM) -n $< > $@ + +# Link: create ELF output file from object files. +.SECONDARY : $(TARGET).elf +.PRECIOUS : $(ALLOBJ) +%.elf: $(ALLOBJ) + @echo $(MSG_LINKING) $@ +# use $(CC) for C-only projects or $(CPP) for C++-projects: + $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) +# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) + + +# Assemble: create object files from assembler source files. +define ASSEMBLE_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING) $$< to $$@ + $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +define ASSEMBLE_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ + $(CC) -c $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C source files. +define COMPILE_C_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +define COMPILE_C_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C++ source files. +define COMPILE_CPP_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +define COMPILE_CPP_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + + +# Compile: create assembler files from C source files. ARM/Thumb +$(SRC:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC) $< to $@ + $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Compile: create assembler files from C source files. ARM only +$(SRCARM:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC_ARM) $< to $@ + $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Target: clean project. +clean: begin clean_list finished end + +clean_list : +## @echo + @echo $(MSG_CLEANING) + $(REMOVE) $(OUTDIR)/$(TARGET).map + $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(REMOVE) $(wildcard $(OUTDIR)/*.h) + $(REMOVE) $(ALLOBJ) + $(REMOVE) $(LSTFILES) + $(REMOVE) $(DEPFILES) + $(REMOVE) $(SRC:.c=.s) + $(REMOVE) $(SRCARM:.c=.s) + $(REMOVE) $(CPPSRC:.cpp=.s) + $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(OUTDIR) 2>NUL) +else +$(shell mkdir $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + + + +# Listing of phony targets. +.PHONY : all begin finish end sizebefore sizeafter gccversion \ +build elf hex bin lss sym clean clean_list program gencode + diff --git a/flight/RevoMini/System/alarms.c b/flight/RevoMini/System/alarms.c new file mode 100644 index 000000000..e61c7c1ea --- /dev/null +++ b/flight/RevoMini/System/alarms.c @@ -0,0 +1,210 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/RevoMini/System/cm3_fault_handlers.c b/flight/RevoMini/System/cm3_fault_handlers.c new file mode 100644 index 000000000..af26e2ad9 --- /dev/null +++ b/flight/RevoMini/System/cm3_fault_handlers.c @@ -0,0 +1,87 @@ +/* + * cm3_fault_handlers.c + * + * Created on: Apr 24, 2011 + * Author: msmith + */ + +#include +#include "dcc_stdio.h" +#ifdef STM32F4XX +# include "stm32f4xx.h" +#endif +#ifdef STM32F2XX +# include "stm32f2xx.h" +#endif + +#define FAULT_TRAMPOLINE(_vec) \ +__attribute__((naked, no_instrument_function)) \ +void \ +_vec##_Handler(void) \ +{ \ + __asm( ".syntax unified\n" \ + "MOVS R0, #4 \n" \ + "MOV R1, LR \n" \ + "TST R0, R1 \n" \ + "BEQ 1f \n" \ + "MRS R0, PSP \n" \ + "B " #_vec "_Handler2 \n" \ + "1: \n" \ + "MRS R0, MSP \n" \ + "B " #_vec "_Handler2 \n" \ + ".syntax divided\n"); \ +} \ +struct hack + +struct cm3_frame { + uint32_t r0; + uint32_t r1; + uint32_t r2; + uint32_t r3; + uint32_t r12; + uint32_t lr; + uint32_t pc; + uint32_t psr; +}; + +FAULT_TRAMPOLINE(HardFault); +FAULT_TRAMPOLINE(BusFault); +FAULT_TRAMPOLINE(UsageFault); + +/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */ +#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg)) + +void +HardFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nHARD FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(HFSR)); + dbg_write_char('\n'); + for (;;); +} + +void +BusFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nBUS FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(CFSR)); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(BFAR)); + dbg_write_char('\n'); + for (;;); +} + +void +UsageFault_Handler2(struct cm3_frame *frame) +{ + dbg_write_str("\nUSAGE FAULT"); + dbg_write_hex32(frame->pc); + dbg_write_char('\n'); + dbg_write_hex32(SCB_REG(CFSR)); + dbg_write_char('\n'); + for (;;); +} diff --git a/flight/RevoMini/System/dcc_stdio.c b/flight/RevoMini/System/dcc_stdio.c new file mode 100644 index 000000000..bf5bd85ad --- /dev/null +++ b/flight/RevoMini/System/dcc_stdio.c @@ -0,0 +1,149 @@ +/*************************************************************************** + * Copyright (C) 2008 by Dominic Rath * + * Dominic.Rath@gmx.de * + * Copyright (C) 2008 by Spencer Oliver * + * spen@spen-soft.co.uk * + * Copyright (C) 2008 by Frederik Kriewtz * + * frederik@kriewitz.eu * + * * + * This program is free software; you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation; either version 2 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * You should have received a copy of the GNU General Public License * + * along with this program; if not, write to the * + * Free Software Foundation, Inc., * + * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * + ***************************************************************************/ + +#include "dcc_stdio.h" + +#define TARGET_REQ_TRACEMSG 0x00 +#define TARGET_REQ_DEBUGMSG_ASCII 0x01 +#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8)) +#define TARGET_REQ_DEBUGCHAR 0x02 + +/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel + * DCRDR[7:0] is used by target for status + * DCRDR[15:8] is used by target for write buffer + * DCRDR[23:16] is used for by host for status + * DCRDR[31:24] is used for by host for write buffer */ + +#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8)) + +#define BUSY 1 + +void dbg_write(unsigned long dcc_data) +{ + int len = 4; + + while (len--) + { + /* wait for data ready */ + while (NVIC_DBG_DATA_R & BUSY); + + /* write our data and set write flag - tell host there is data*/ + NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY); + dcc_data >>= 8; + } +} + +void dbg_trace_point(unsigned long number) +{ + dbg_write(TARGET_REQ_TRACEMSG | (number << 8)); +} + +void dbg_write_u32(const unsigned long *val, long len) +{ + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dbg_write(*val); + + val++; + len--; + } +} + +void dbg_write_u16(const unsigned short *val, long len) +{ + unsigned long dcc_data; + + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = val[0] + | ((len > 1) ? val[1] << 16: 0x0000); + + dbg_write(dcc_data); + + val += 2; + len -= 2; + } +} + +void dbg_write_u8(const unsigned char *val, long len) +{ + unsigned long dcc_data; + + dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = val[0] + | ((len > 1) ? val[1] << 8 : 0x00) + | ((len > 2) ? val[2] << 16 : 0x00) + | ((len > 3) ? val[3] << 24 : 0x00); + + dbg_write(dcc_data); + + val += 4; + len -= 4; + } +} + +void dbg_write_str(const char *msg) +{ + long len; + unsigned long dcc_data; + + for (len = 0; msg[len] && (len < 65536); len++); + + dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16)); + + while (len > 0) + { + dcc_data = msg[0] + | ((len > 1) ? msg[1] << 8 : 0x00) + | ((len > 2) ? msg[2] << 16 : 0x00) + | ((len > 3) ? msg[3] << 24 : 0x00); + dbg_write(dcc_data); + + msg += 4; + len -= 4; + } +} + +void dbg_write_char(char msg) +{ + dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16)); +} + +void dbg_write_hex32(const unsigned long val) +{ + static const char hextab[] = { + '0', '1', '2', '3', '4', '5', '6', '7', + '8', '9', 'a', 'b', 'c', 'd', 'e', 'f' + }; + + for (int shift = 28; shift >= 0; shift -= 4) + dbg_write_char(hextab[(val >> shift) & 0xf]); +} diff --git a/flight/RevoMini/System/inc/FreeRTOSConfig.h b/flight/RevoMini/System/inc/FreeRTOSConfig.h new file mode 100644 index 000000000..72d6e288a --- /dev/null +++ b/flight/RevoMini/System/inc/FreeRTOSConfig.h @@ -0,0 +1,103 @@ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/** + * @addtogroup PIOS PIOS + * @{ + * @addtogroup FreeRTOS FreeRTOS + * @{ + */ + +/* Notes: We use 5 task priorities */ + +#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... +#define configTICK_RATE_HZ ((portTickType )1000) +#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) +#define configMINIMAL_STACK_SIZE ((unsigned short)512) +#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total +#define configMAX_TASK_NAME_LEN (16) + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +//#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 1 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +/* Enable run time stats collection */ +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 + +/* + * Once we move to CMSIS2 we can at least use: + * + * CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + * + * (still nothing for the DWT registers, surprisingly) + */ +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ + do { \ + (*(unsigned long *)0xe000edfc) |= (1<<24); /* DEMCR |= DEMCR_TRCENA */ \ + (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \ + } while(0) +#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */ + + +/** + * @} + */ + +#endif /* FREERTOS_CONFIG_H */ diff --git a/flight/RevoMini/System/inc/alarms.h b/flight/RevoMini/System/inc/alarms.h new file mode 100644 index 000000000..9fb047dca --- /dev/null +++ b/flight/RevoMini/System/inc/alarms.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} + */ diff --git a/flight/RevoMini/System/inc/dcc_stdio.h b/flight/RevoMini/System/inc/dcc_stdio.h new file mode 100644 index 000000000..dbfd39342 --- /dev/null +++ b/flight/RevoMini/System/inc/dcc_stdio.h @@ -0,0 +1,36 @@ +/*************************************************************************** + * Copyright (C) 2008 by Dominic Rath * + * Dominic.Rath@gmx.de * + * Copyright (C) 2008 by Spencer Oliver * + * spen@spen-soft.co.uk * + * * + * This program is free software; you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation; either version 2 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * You should have received a copy of the GNU General Public License * + * along with this program; if not, write to the * + * Free Software Foundation, Inc., * + * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * + ***************************************************************************/ + +#ifndef DCC_STDIO_H +#define DCC_STDIO_H + +void dbg_trace_point(unsigned long number); + +void dbg_write_u32(const unsigned long *val, long len); +void dbg_write_u16(const unsigned short *val, long len); +void dbg_write_u8(const unsigned char *val, long len); + +void dbg_write_str(const char *msg); +void dbg_write_char(char msg); +void dbg_write_hex32(const unsigned long val); + +#endif /* DCC_STDIO_H */ diff --git a/flight/RevoMini/System/inc/op_config.h b/flight/RevoMini/System/inc/op_config.h new file mode 100644 index 000000000..97910f392 --- /dev/null +++ b/flight/RevoMini/System/inc/op_config.h @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file op_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief OpenPilot configuration header. + * Compile time config for OpenPilot Application + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OP_CONFIG_H +#define OP_CONFIG_H + +#endif /* OP_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/RevoMini/System/inc/openpilot.h b/flight/RevoMini/System/inc/openpilot.h new file mode 100644 index 000000000..59ae76fd4 --- /dev/null +++ b/flight/RevoMini/System/inc/openpilot.h @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "op_config.h" +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} + */ diff --git a/flight/RevoMini/System/inc/pios_board_sim.h b/flight/RevoMini/System/inc/pios_board_sim.h new file mode 100644 index 000000000..30a3d3d37 --- /dev/null +++ b/flight/RevoMini/System/inc/pios_board_sim.h @@ -0,0 +1,85 @@ +/** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_ALARM 0 +#define PIOS_LED_HEARTBEAT 1 +#define PIOS_LED_NUM 2 + +//------------------------- +// COM +// +// See also pios_board_posix.c +//------------------------- +//#define PIOS_USART_TX_BUFFER_SIZE 256 +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_COM_MAX_DEVS 255 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE +#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_spectrum_id; + +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_GPS (pios_com_gps_id) + +#ifdef PIOS_ENABLE_AUX_UART +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_DEBUG (PIOS_COM_AUX +#endif + +#define PIOS_GCSRCVR_TIMEOUT_MS 200 +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL + +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL + +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) + + + +#define PIOS_FCLOSE(file) fclose(file) + +#define PIOS_FUNLINK(file) unlink((char*)filename) + +#endif /* PIOS_BOARD_H */ diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h new file mode 100644 index 000000000..4bb7be2a7 --- /dev/null +++ b/flight/RevoMini/System/inc/pios_config.h @@ -0,0 +1,122 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Major features */ +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_BL_HELPER + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +//#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_WDG + +/* Select the sensors to include */ +#define PIOS_INCLUDE_BMA180 +#define PIOS_INCLUDE_HMC5883 +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL +#define PIOS_INCLUDE_L3GD20 +#define PIOS_INCLUDE_MS5611 +#define PIOS_INCLUDE_ETASV3 +//#define PIOS_INCLUDE_HCSR04 +#define PIOS_FLASH_ON_ACCEL /* true for second revo */ +#define FLASH_FREERTOS +/* Com systems to include */ +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_COM_AUX +#define PIOS_INCLUDE_COM_AUXSBUS +#define PIOS_INCLUDE_COM_FLEXI + +#define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +#define PIOS_GPS_SETS_HOMELOCATION + +#define PIOS_OVERO_SPI +/* Supported receiver interfaces */ +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_DSM +//#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_GCSRCVR + +#define PIOS_INCLUDE_SETTINGS +#define PIOS_INCLUDE_FLASH +/* A really shitty setting saving implementation */ +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS + +/* Other Interfaces */ +//#define PIOS_INCLUDE_I2C_ESC + +/* Flags that alter behaviors - mostly to lower resources for CC */ +#define PIOS_INCLUDE_INITCALL /* Include init call structures */ +#define PIOS_TELEM_PRIORITY_QUEUE /* Enable a priority queue in telemetry */ +//#define PIOS_QUATERNION_STABILIZATION /* Stabilization options */ +#define PIOS_GPS_SETS_HOMELOCATION /* GPS options */ + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 1000 +#define HEAP_LIMIT_CRITICAL 500 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +// This actually needs calibrating +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (8379692) + +#define REVOLUTION + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/RevoMini/System/inc/pios_config_sim.h b/flight/RevoMini/System/inc/pios_config_sim.h new file mode 100644 index 000000000..e7f7aed82 --- /dev/null +++ b/flight/RevoMini/System/inc/pios_config_sim.h @@ -0,0 +1,79 @@ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +//#define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_TELEMETRY_RF +#define PIOS_INCLUDE_TCP +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_GCSRCVR + +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_RCVR_MAX_DEVS 3 + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 2048 + +/* Stabilization options */ +#define PIOS_QUATERNION_STABILIZATION + +/* GPS options */ +#define PIOS_GPS_SETS_HOMELOCATION + +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +#define REVOLUTION + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/RevoMini/System/inc/pios_usb_board_data.h b/flight/RevoMini/System/inc/pios_usb_board_data.h new file mode 100644 index 000000000..0e5dd8181 --- /dev/null +++ b/flight/RevoMini/System/inc/pios_usb_board_data.h @@ -0,0 +1,46 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64 +#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32 +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 4 + +#include "pios_usb_defs.h" /* USB_* macros */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_FW) +#define PIOS_USB_BOARD_SN_SUFFIX "+FW" + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c new file mode 100644 index 000000000..b9360bfef --- /dev/null +++ b/flight/RevoMini/System/pios_board.c @@ -0,0 +1,885 @@ +/** + ****************************************************************************** + * @addtogroup Revolution Revolution configuration files + * @{ + * @brief Configures the revolution board + * @{ + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Defines board specific static initializers for hardware for the Revolution board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Pull in the board-specific static HW definitions. + * Including .c files is a bit ugly but this allows all of + * the HW definitions to be const and static to limit their + * scope. + * + * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE + */ +#include "board_hw_defs.c" + +#include +#include +#include +#include "hwsettings.h" +#include "manualcontrolsettings.h" + +/** + * Sensor configurations + */ + +#if defined(PIOS_INCLUDE_ADC) +#include "pios_adc_priv.h" +void PIOS_ADC_DMC_irq_handler(void); +void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler"))); +struct pios_adc_cfg pios_adc_cfg = { + .adc_dev = ADC1, + .dma = { + .irq = { + .flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4), + .init = { + .NVIC_IRQChannel = DMA2_Stream4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .channel = DMA2_Stream4, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR + }, + } + }, + .half_flag = DMA_IT_HTIF4, + .full_flag = DMA_IT_TCIF4, + +}; +void PIOS_ADC_DMC_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_ADC_DMA_Handler(); +} + +#endif + +#if defined(PIOS_INCLUDE_HMC5883) +#include "pios_hmc5883.h" +static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { + .vector = PIOS_HMC5883_IRQHandler, + .line = EXTI_Line5, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line5, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { + .exti_cfg = &pios_exti_hmc5883_cfg, + .M_ODR = PIOS_HMC5883_ODR_75, + .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, + .Gain = PIOS_HMC5883_GAIN_1_9, + .Mode = PIOS_HMC5883_MODE_CONTINUOUS, + +}; +#endif /* PIOS_INCLUDE_HMC5883 */ + +/** + * Configuration for the MS5611 chip + */ +#if defined(PIOS_INCLUDE_MS5611) +#include "pios_ms5611.h" +static const struct pios_ms5611_cfg pios_ms5611_cfg = { + .oversampling = 1, +}; +#endif /* PIOS_INCLUDE_MS5611 */ + +/** + * Configuration for the BMA180 chip + */ +#if defined(PIOS_INCLUDE_BMA180) +#include "pios_bma180.h" +static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = { + .vector = PIOS_BMA180_IRQHandler, + .line = EXTI_Line4, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line4, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; +static const struct pios_bma180_cfg pios_bma180_cfg = { + .exti_cfg = &pios_exti_bma180_cfg, + .bandwidth = BMA_BW_600HZ, + .range = BMA_RANGE_8G, +}; +#endif /* PIOS_INCLUDE_BMA180 */ + +/** + * Configuration for the MPU6000 chip + */ +#if defined(PIOS_INCLUDE_MPU6000) +#include "pios_mpu6000.h" +static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { + .vector = PIOS_MPU6000_IRQHandler, + .line = EXTI_Line8, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line8, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { + .exti_cfg = &pios_exti_mpu6000_cfg, + .Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT, + // Clock at 8 khz, downsampled by 8 for 1khz + .Smpl_rate_div = 11, + .interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD, + .interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY, + .User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C, + .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, + .accel_range = PIOS_MPU6000_ACCEL_8G, + .gyro_range = PIOS_MPU6000_SCALE_500_DEG, + .filter = PIOS_MPU6000_LOWPASS_256_HZ +}; +#endif /* PIOS_INCLUDE_MPU6000 */ + +/** + * Configuration for L3GD20 chip + */ +#if defined(PIOS_INCLUDE_L3GD20) +#include "pios_l3gd20.h" +static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = { + .vector = PIOS_L3GD20_IRQHandler, + .line = EXTI_Line8, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line8, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_l3gd20_cfg pios_l3gd20_cfg = { + .exti_cfg = &pios_exti_l3gd20_cfg, + .range = PIOS_L3GD20_SCALE_500_DEG, +}; +#endif /* PIOS_INCLUDE_L3GD20 */ + + +static const struct flashfs_cfg flashfs_m25p_cfg = { + .table_magic = 0x85FB3D35, + .obj_magic = 0x3015A371, + .obj_table_start = 0x00000010, + .obj_table_end = 0x00010000, + .sector_size = 0x00010000, + .chip_size = 0x00200000, +}; + +static const struct pios_flash_jedec_cfg flash_m25p_cfg = { + .sector_erase = 0xD8, + .chip_erase = 0xC7 +}; + +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 + +#define PIOS_COM_GPS_RX_BUF_LEN 32 + +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 + +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 + +#define PIOS_COM_AUX_RX_BUF_LEN 512 +#define PIOS_COM_AUX_TX_BUF_LEN 512 + +uint32_t pios_com_aux_id = 0; +uint32_t pios_com_gps_id = 0; +uint32_t pios_com_telem_usb_id = 0; +uint32_t pios_com_telem_rf_id = 0; +uint32_t pios_com_bridge_id = 0; +uint32_t pios_com_overo_id = 0; + +/* + * Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only + */ +static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uint32_t *pios_com_id) +{ + uint32_t pios_usart_id; + if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(rx_buf_len); + PIOS_Assert(rx_buffer); + if(tx_buf_len!= -1){ // this is the case for rx/tx ports + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(tx_buf_len); + PIOS_Assert(tx_buffer); + + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + tx_buffer, tx_buf_len)) { + PIOS_Assert(0); + } + } + else{ //rx only port + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + NULL, 0)) { + PIOS_Assert(0); + } + } +} + +static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, + const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) +{ + uint32_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + pios_usart_dsm_id, *proto, *bind)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; +} + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ + +#include + +void PIOS_Board_Init(void) { + + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + /* Delay system */ + PIOS_DELAY_Init(); + + PIOS_LED_Init(&pios_led_cfg); + + /* Set up the SPI interface to the accelerometer*/ + if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { + PIOS_DEBUG_Assert(0); + } + + /* Set up the SPI interface to the gyro */ + if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { + PIOS_DEBUG_Assert(0); + } +#if !defined(PIOS_FLASH_ON_ACCEL) + /* Set up the SPI interface to the flash */ + if (PIOS_SPI_Init(&pios_spi_flash_id, &pios_spi_flash_cfg)) { + PIOS_DEBUG_Assert(0); + } + PIOS_Flash_Jedec_Init(pios_spi_flash_id, 0, &flash_m25p_cfg); +#else + PIOS_Flash_Jedec_Init(pios_spi_accel_id, 1, &flash_m25p_cfg); +#endif + PIOS_FLASHFS_Init(&flashfs_m25p_cfg); + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + + HwSettingsInitialize(); + +#if defined(PIOS_INCLUDE_RTC) + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif + + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); + PIOS_TIM_InitClock(&tim_5_cfg); + PIOS_TIM_InitClock(&tim_9_cfg); + PIOS_TIM_InitClock(&tim_10_cfg); + PIOS_TIM_InitClock(&tim_11_cfg); + + /* IAP System Setup */ + PIOS_IAP_Init(); + uint16_t boot_count = PIOS_IAP_ReadBootCount(); + if (boot_count < 3) { + PIOS_IAP_WriteBootCount(++boot_count); + AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); + } else { + /* Too many failed boot attempts, force hwsettings to defaults */ + HwSettingsSetDefaults(HwSettingsHandle(), 0); + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); + } + + + //PIOS_IAP_Init(); + +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Flags to determine if various USB interfaces are advertised */ + bool usb_hid_present = false; + bool usb_cdc_present = false; + +#if defined(PIOS_INCLUDE_USB_CDC) + if (PIOS_USB_DESC_HID_CDC_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + usb_cdc_present = true; +#else + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; +#endif + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_CDC) + + uint8_t hwsettings_usb_vcpport; + /* Configure the USB VCP port */ + HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport); + + if (!usb_cdc_present) { + /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ + hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED; + } + + switch (hwsettings_usb_vcpport) { + case HWSETTINGS_USB_VCPPORT_DISABLED: + break; + case HWSETTINGS_USB_VCPPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_TELEM_USB_RX_BUF_LEN, PIOS_COM_TELEM_USB_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_telem_usb_id); +#endif /* PIOS_INCLUDE_COM */ + break; + case HWSETTINGS_USB_VCPPORT_COMBRIDGE: +#if defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usb_cdc_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usb_cdc_com_driver, &pios_com_vcp_id); +#endif /* PIOS_INCLUDE_COM */ + break; + } +#endif /* PIOS_INCLUDE_USB_CDC */ + +#if defined(PIOS_INCLUDE_USB_HID) + /* Configure the usb HID port */ + uint8_t hwsettings_usb_hidport; + HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport); + + if (!usb_hid_present) { + /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ + hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED; + } + + switch (hwsettings_usb_hidport) { + case HWSETTINGS_USB_HIDPORT_DISABLED: + break; + case HWSETTINGS_USB_HIDPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + { + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } + +#endif /* PIOS_INCLUDE_USB_HID */ + + if (usb_hid_present || usb_cdc_present) { + PIOS_USBHOOK_Activate(); + } +#endif /* PIOS_INCLUDE_USB */ + + /* Configure IO ports */ + uint8_t hwsettings_DSMxBind; + HwSettingsDSMxBindGet(&hwsettings_DSMxBind); + + /* Configure Telemetry port */ + uint8_t hwsettings_rv_telemetryport; + HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport); + + switch (hwsettings_rv_telemetryport){ + case HWSETTINGS_RV_TELEMETRYPORT_DISABLED: + break; + case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + case HWSETTINGS_RV_TELEMETRYPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + + } /* hwsettings_rv_telemetryport */ + + /* Configure GPS port */ + uint8_t hwsettings_rv_gpsport; + HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport); + switch (hwsettings_rv_gpsport){ + case HWSETTINGS_RV_GPSPORT_DISABLED: + break; + + case HWSETTINGS_RV_GPSPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_GPSPORT_GPS: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); + break; + + case HWSETTINGS_RV_GPSPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + + case HWSETTINGS_RV_GPSPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + }/* hwsettings_rv_gpsport */ + + /* Configure AUXPort */ + uint8_t hwsettings_rv_auxport; + HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport); + + switch (hwsettings_rv_auxport) { + case HWSETTINGS_RV_AUXPORT_DISABLED: + break; + + case HWSETTINGS_RV_AUXPORT_TELEMETRY: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + + case HWSETTINGS_RV_AUXPORT_DSM2: + case HWSETTINGS_RV_AUXPORT_DSMX10BIT: + case HWSETTINGS_RV_AUXPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_auxport) { + case HWSETTINGS_RV_AUXPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_AUXPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_AUXPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_aux_cfg, &pios_dsm_aux_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_AUXPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_AUXPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_auxport */ + /* Configure AUXSbusPort */ + //TODO: ensure that the serial invertion pin is setted correctly + uint8_t hwsettings_rv_auxsbusport; + HwSettingsRV_AuxSBusPortGet(&hwsettings_rv_auxsbusport); + + switch (hwsettings_rv_auxsbusport) { + case HWSETTINGS_RV_AUXSBUSPORT_DISABLED: + break; + case HWSETTINGS_RV_AUXSBUSPORT_SBUS: +#ifdef PIOS_INCLUDE_SBUS + { + uint32_t pios_usart_sbus_id; + if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_id; + if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_rcvr_id; + if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; + + } +#endif /* PIOS_INCLUDE_SBUS */ + break; + + case HWSETTINGS_RV_AUXSBUSPORT_DSM2: + case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: + case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_auxsbusport) { + case HWSETTINGS_RV_AUXSBUSPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_auxsbus_cfg, &pios_dsm_auxsbus_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_AUXSBUSPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_auxport */ + + /* Configure FlexiPort */ + + uint8_t hwsettings_rv_flexiport; + HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport); + + switch (hwsettings_rv_flexiport) { + case HWSETTINGS_RV_FLEXIPORT_DISABLED: + break; + case HWSETTINGS_RV_FLEXIPORT_I2C: +#if defined(PIOS_INCLUDE_I2C) + { + if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_I2C */ + break; + + case HWSETTINGS_RV_FLEXIPORT_DSM2: + case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: + case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_rv_flexiport) { + case HWSETTINGS_RV_FLEXIPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; + case HWSETTINGS_RV_FLEXIPORT_COMAUX: + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + break; + case HWSETTINGS_RV_FLEXIPORT_COMBRIDGE: + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + } /* hwsettings_rv_flexiport */ + + + /* Configure the receiver port*/ + uint8_t hwsettings_rcvrport; + HwSettingsRV_RcvrPortGet(&hwsettings_rcvrport); + // + switch (hwsettings_rcvrport){ + case HWSETTINGS_RV_RCVRPORT_DISABLED: + break; + case HWSETTINGS_RV_RCVRPORT_PWM: +#if defined(PIOS_INCLUDE_PWM) + { + /* Set up the receiver port. Later this should be optional */ + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uint32_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + case HWSETTINGS_RV_RCVRPORT_PPM: + case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS: +#if defined(PIOS_INCLUDE_PPM) + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uint32_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PPM */ + case HWSETTINGS_RV_RCVRPORT_OUTPUTS: + + break; + } + +#if defined(PIOS_OVERO_SPI) + /* Set up the SPI based PIOS_COM interface to the overo */ + { + HwSettingsData hwSettings; + HwSettingsGet(&hwSettings); + if(hwSettings.OptionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { + PIOS_DEBUG_Assert(0); + } + const uint32_t PACKET_SIZE = 1024; + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, + rx_buffer, PACKET_SIZE, + tx_buffer, PACKET_SIZE)) { + PIOS_Assert(0); + } + } + } + +#endif + +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uint32_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + switch (hwsettings_rcvrport) { + case HWSETTINGS_RV_RCVRPORT_DISABLED: + case HWSETTINGS_RV_RCVRPORT_PWM: + case HWSETTINGS_RV_RCVRPORT_PPM: + /* Set up the servo outputs */ + PIOS_Servo_Init(&pios_servo_cfg); + break; + case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS: + case HWSETTINGS_RV_RCVRPORT_OUTPUTS: + //PIOS_Servo_Init(&pios_servo_rcvr_cfg); + //TODO: Prepare the configurations on board_hw_defs and handle here: + PIOS_Servo_Init(&pios_servo_cfg); + break; + } +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif + + if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) { + PIOS_DEBUG_Assert(0); + } + + if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) { + PIOS_DEBUG_Assert(0); + } + + PIOS_DELAY_WaitmS(50); + +#if defined(PIOS_INCLUDE_ADC) + PIOS_ADC_Init(&pios_adc_cfg); +#endif + +#if defined(PIOS_INCLUDE_HMC5883) + PIOS_HMC5883_Init(&pios_hmc5883_cfg); +#endif + +#if defined(PIOS_INCLUDE_MS5611) + PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id); +#endif + + switch(bdinfo->board_rev) { + case 0x01: +#if defined(PIOS_INCLUDE_L3GD20) + PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg); + PIOS_Assert(PIOS_L3GD20_Test() == 0); +#endif +#if defined(PIOS_INCLUDE_BMA180) + PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg); + PIOS_Assert(PIOS_BMA180_Test() == 0); +#endif + break; + case 0x02: +#if defined(PIOS_INCLUDE_MPU6000) + PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg); +#endif + break; + default: + PIOS_DEBUG_Assert(0); + } + +} + +/** + * @} + * @} + */ + diff --git a/flight/RevoMini/System/pios_board_sim.c b/flight/RevoMini/System/pios_board_sim.c new file mode 100644 index 000000000..07ae969fb --- /dev/null +++ b/flight/RevoMini/System/pios_board_sim.c @@ -0,0 +1,229 @@ +/** + ****************************************************************************** + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include +#include +#include +#include +#include + +#include "accels.h" +#include "baroaltitude.h" +#include "gpsposition.h" +#include "gyros.h" +#include "gyrosbias.h" +#include "magnetometer.h" +#include "manualcontrolsettings.h" + +#include "pios_rcvr_priv.h" +#include "pios_gcsrcvr_priv.h" + +void Stack_Change() { +} + +void Stack_Change_Weak() { +} + + +const struct pios_tcp_cfg pios_tcp_telem_cfg = { + .ip = "0.0.0.0", + .port = 9001, +}; + +const struct pios_udp_cfg pios_udp_telem_cfg = { + .ip = "0.0.0.0", + .port = 9001, +}; + +const struct pios_tcp_cfg pios_tcp_gps_cfg = { + .ip = "0.0.0.0", + .port = 9001, +}; +const struct pios_tcp_cfg pios_tcp_debug_cfg = { + .ip = "0.0.0.0", + .port = 9002, +}; + +#ifdef PIOS_COM_AUX +/* + * AUX USART + */ +const struct pios_tcp_cfg pios_tcp_aux_cfg = { + .ip = "0.0.0.0", + .port = 9003, +}; +#endif + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 +#define PIOS_COM_GPS_RX_BUF_LEN 96 + +/* + * Board specific number of devices. + */ +/* +struct pios_udp_dev pios_udp_devs[] = { +#define PIOS_UDP_TELEM 0 + { + .cfg = &pios_udp0_cfg, + }, +#define PIOS_UDP_GPS 1 + { + .cfg = &pios_udp1_cfg, + }, +#define PIOS_UDP_LOCAL 2 + { + .cfg = &pios_udp2_cfg, + }, +#ifdef PIOS_COM_AUX +#define PIOS_UDP_AUX 3 + { + .cfg = &pios_udp3_cfg, + }, +#endif +}; + +uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs); +*/ +/* + * COM devices + */ + +/* + * Board specific number of devices. + */ +extern const struct pios_com_driver pios_serial_com_driver; +extern const struct pios_com_driver pios_udp_com_driver; +extern const struct pios_com_driver pios_tcp_com_driver; + +uint32_t pios_com_telem_rf_id; +uint32_t pios_com_telem_usb_id; +uint32_t pios_com_gps_id; +uint32_t pios_com_aux_id; +uint32_t pios_com_spectrum_id; +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +/** + * PIOS_Board_Init() + * initializes all the core systems on this specific hardware + * called from System/openpilot.c + */ +void PIOS_Board_Init(void) { + + /* Delay system */ + PIOS_DELAY_Init(); + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + UAVObjectsInitializeAll(); + + AccelsInitialize(); + BaroAltitudeInitialize(); + MagnetometerInitialize(); + GPSPositionInitialize(); + GyrosInitialize(); + GyrosBiasInitialize(); + + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + +#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && 1 + { + uint32_t pios_tcp_telem_rf_id; + if (PIOS_TCP_Init(&pios_tcp_telem_rf_id, &pios_tcp_telem_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_tcp_com_driver, pios_tcp_telem_rf_id, + rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && 0 + { + uint32_t pios_udp_telem_rf_id; + if (PIOS_UDP_Init(&pios_udp_telem_rf_id, &pios_udp_telem_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_udp_com_driver, pios_udp_telem_rf_id, + rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + + +#if defined(PIOS_INCLUDE_GPS) + { + uint32_t pios_tcp_gps_id; + if (PIOS_TCP_Init(&pios_tcp_gps_id, &pios_tcp_gps_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); + PIOS_Assert(rx_buffer); + if (PIOS_COM_Init(&pios_com_gps_id, &pios_tcp_com_driver, pios_tcp_gps_id, + rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, + NULL, 0)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_GPS */ +#endif + +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uint32_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + +} + +/** + * @} + */ diff --git a/flight/RevoMini/System/pios_usb_board_data.c b/flight/RevoMini/System/pios_usb_board_data.c new file mode 100644 index 000000000..0fb67116d --- /dev/null +++ b/flight/RevoMini/System/pios_usb_board_data.c @@ -0,0 +1,98 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ + +static const uint8_t usb_product_id[22] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'R', 0, + 'e', 0, + 'v', 0, + 'o', 0, + 'l', 0, + 'u', 0, + 't', 0, + 'i', 0, + 'o', 0, + 'n', 0, +}; + +static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_US), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; + PIOS_SYS_SerialNumberGet((char *)sn); + + /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ + uint8_t * utf8 = &(usb_serial_number[2]); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); + utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/RevoMini/System/revolution.c b/flight/RevoMini/System/revolution.c new file mode 100644 index 000000000..ff2814fbd --- /dev/null +++ b/flight/RevoMini/System/revolution.c @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Local Variables */ +#define INCLUDE_TEST_TASKS 0 +#if INCLUDE_TEST_TASKS +static uint8_t sdcard_available; +#endif +char Buffer[1024]; +uint32_t Cache; + +/* Function Prototypes */ +#if INCLUDE_TEST_TASKS +static void TaskTick(void *pvParameters); +static void TaskTesting(void *pvParameters); +static void TaskHIDTest(void *pvParameters); +static void TaskServos(void *pvParameters); +static void TaskSDCard(void *pvParameters); +#endif +int32_t CONSOLE_Parse(uint8_t port, char c); +void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +/* Function Prototypes */ +static void initTask(void *parameters); + +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + int result; + + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + vPortInitialiseBlocks(); + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler */ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +/** + * @} + * @} + */ + diff --git a/flight/RevoMini/UAVObjects.inc b/flight/RevoMini/UAVObjects.inc new file mode 100644 index 000000000..5b99daef4 --- /dev/null +++ b/flight/RevoMini/UAVObjects.inc @@ -0,0 +1,96 @@ +##### +# Project: OpenPilot +# +# Makefile for OpenPilot UAVObject code +# +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +##### + +# These are the UAVObjects supposed to be build as part of the OpenPilot target +# (all architectures) + +UAVOBJSRCFILENAMES = +UAVOBJSRCFILENAMES += accessorydesired +UAVOBJSRCFILENAMES += actuatorcommand +UAVOBJSRCFILENAMES += actuatordesired +UAVOBJSRCFILENAMES += actuatorsettings +UAVOBJSRCFILENAMES += altholdsmoothed +UAVOBJSRCFILENAMES += attitudesettings +UAVOBJSRCFILENAMES += attitudeactual +UAVOBJSRCFILENAMES += gyros +UAVOBJSRCFILENAMES += gyrosbias +UAVOBJSRCFILENAMES += accels +UAVOBJSRCFILENAMES += magnetometer +UAVOBJSRCFILENAMES += magbias +UAVOBJSRCFILENAMES += baroaltitude +UAVOBJSRCFILENAMES += baroairspeed +UAVOBJSRCFILENAMES += fixedwingpathfollowersettings +UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus +UAVOBJSRCFILENAMES += flightbatterysettings +UAVOBJSRCFILENAMES += firmwareiapobj +UAVOBJSRCFILENAMES += flightbatterystate +UAVOBJSRCFILENAMES += flightplancontrol +UAVOBJSRCFILENAMES += flightplansettings +UAVOBJSRCFILENAMES += flightplanstatus +UAVOBJSRCFILENAMES += flighttelemetrystats +UAVOBJSRCFILENAMES += gcstelemetrystats +UAVOBJSRCFILENAMES += gcsreceiver +UAVOBJSRCFILENAMES += gpsposition +UAVOBJSRCFILENAMES += gpssatellites +UAVOBJSRCFILENAMES += gpssettings +UAVOBJSRCFILENAMES += gpstime +UAVOBJSRCFILENAMES += gpsvelocity +UAVOBJSRCFILENAMES += vtolpathfollowersettings +UAVOBJSRCFILENAMES += homelocation +UAVOBJSRCFILENAMES += i2cstats +UAVOBJSRCFILENAMES += manualcontrolcommand +UAVOBJSRCFILENAMES += manualcontrolsettings +UAVOBJSRCFILENAMES += mixersettings +UAVOBJSRCFILENAMES += mixerstatus +UAVOBJSRCFILENAMES += nedaccel +UAVOBJSRCFILENAMES += nedposition +UAVOBJSRCFILENAMES += objectpersistence +UAVOBJSRCFILENAMES += overosyncstats +UAVOBJSRCFILENAMES += overosyncsettings +UAVOBJSRCFILENAMES += pathplannersettings +UAVOBJSRCFILENAMES += pathdesired +UAVOBJSRCFILENAMES += positionactual +UAVOBJSRCFILENAMES += ratedesired +UAVOBJSRCFILENAMES += revocalibration +UAVOBJSRCFILENAMES += revosettings +UAVOBJSRCFILENAMES += sonaraltitude +UAVOBJSRCFILENAMES += stabilizationdesired +UAVOBJSRCFILENAMES += stabilizationsettings +UAVOBJSRCFILENAMES += systemalarms +UAVOBJSRCFILENAMES += systemsettings +UAVOBJSRCFILENAMES += systemstats +UAVOBJSRCFILENAMES += taskinfo +UAVOBJSRCFILENAMES += velocityactual +UAVOBJSRCFILENAMES += velocitydesired +UAVOBJSRCFILENAMES += watchdogstatus +UAVOBJSRCFILENAMES += flightstatus +UAVOBJSRCFILENAMES += hwsettings +UAVOBJSRCFILENAMES += receiveractivity +UAVOBJSRCFILENAMES += cameradesired +UAVOBJSRCFILENAMES += camerastabsettings +UAVOBJSRCFILENAMES += altitudeholdsettings +UAVOBJSRCFILENAMES += altitudeholddesired +UAVOBJSRCFILENAMES += waypoint +UAVOBJSRCFILENAMES += waypointactive + +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c new file mode 100644 index 000000000..b54dd119d --- /dev/null +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -0,0 +1,1823 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * + * @file board_hw_defs.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board specific static initializers for hardware for the OpenPilot board. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include +#include + +#if defined(PIOS_INCLUDE_LED) + +#include +static const struct pios_led pios_leds[] = { + [PIOS_LED_HEARTBEAT] = { + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, + [PIOS_LED_ALARM] = { + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, +}; + +static const struct pios_led_cfg pios_led_cfg = { + .leds = pios_leds, + .num_leds = NELEMENTS(pios_leds), +}; + +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +{ + return &pios_led_cfg; +} + +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_SPI) +#include +/* SPI1 Interface + * - Used for BMA180 accelerometer + */ +void PIOS_SPI_accel_irq_handler(void); +void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); +void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); +static const struct pios_spi_cfg pios_spi_accel_cfg = { + .regs = SPI1, + .remap = GPIO_AF_SPI1, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, + }, + .use_crc = false, + .dma = { + .irq = { + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { + .NVIC_IRQChannel = DMA2_Stream0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA2_Stream0, + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + /* .DMA_FIFOThreshold */ + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA2_Stream3, + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + /* .DMA_FIFOThreshold */ + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .miso = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .mosi = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .slave_count = 2, + .ssel = { { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + } }, + { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + } }, + } +}; + +static uint32_t pios_spi_accel_id; +void PIOS_SPI_accel_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_accel_id); +} + + +/* SPI2 Interface + * - Used for gyro communications + */ +void PIOS_SPI_GYRO_irq_handler(void); +void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +void DMA1_Stream4_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +static const struct pios_spi_cfg pios_spi_gyro_cfg = { + .regs = SPI2, + .remap = GPIO_AF_SPI2, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF3 | DMA_IT_TEIF3 | DMA_IT_HTIF3), + .init = { + .NVIC_IRQChannel = DMA1_Stream3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream3, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream4, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_gyro_id; +void PIOS_SPI_gyro_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_gyro_id); +} + + +#if !defined(PIOS_FLASH_ON_ACCEL) +/* SPI3 Interface + * - Used for flash communications + */ +void PIOS_SPI_flash_irq_handler(void); +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); +void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); +static const struct pios_spi_cfg pios_spi_flash_cfg = { + .regs = SPI3, + .remap = GPIO_AF_SPI3, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { + .NVIC_IRQChannel = DMA1_Stream0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream0, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream5, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_flash_id; +void PIOS_SPI_flash_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_flash_id); +} +#endif /* PIOS_FLASH_ON_ACCEL */ + +#endif /* PIOS_INCLUDE_SPI */ + +#if defined(PIOS_OVERO_SPI) +/* SPI3 Interface + * - Used for flash communications + */ +#include +void PIOS_OVERO_irq_handler(void); +void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); +static const struct pios_overo_cfg pios_overo_cfg = { + .regs = SPI3, + .remap = GPIO_AF_SPI3, + .init = { + .SPI_Mode = SPI_Mode_Slave, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Hard, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case TX) + .flags = (DMA_IT_TCIF7), + .init = { + .NVIC_IRQChannel = DMA1_Stream7_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Stream0, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Circular, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream7, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Circular, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; +uint32_t pios_overo_id = 0; +void PIOS_OVERO_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_OVERO_DMA_irq_handler(pios_overo_id); +} +#else + +#endif /* PIOS_OVERO_SPI */ + + + + + +#include + +#ifdef PIOS_INCLUDE_COM_TELEM +/* + * Telemetry on main USART + */ +static const struct pios_usart_cfg pios_usart_telem_cfg = { + .regs = USART2, + .remap = GPIO_AF_USART2, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_COM_TELEM */ + +#ifdef PIOS_INCLUDE_GPS +/* + * GPS USART + */ +static const struct pios_usart_cfg pios_usart_gps_cfg = { + .regs = USART1, + .remap = GPIO_AF_USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_GPS */ + +#ifdef PIOS_INCLUDE_COM_AUX +/* + * AUX USART (UART label on rev2) + */ +static const struct pios_usart_cfg pios_usart_aux_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_COM_AUX */ + +#ifdef PIOS_INCLUDE_COM_AUXSBUS +/* + * AUX USART SBUS ( UART/ S Bus label on rev2) + */ +static const struct pios_usart_cfg pios_usart_auxsbus_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_COM_AUXSBUS */ + +#ifdef PIOS_INCLUDE_COM_FLEXI +/* + * FLEXI PORT + */ +static const struct pios_usart_cfg pios_usart_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = + USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_COM_FLEXI */ + +#if defined(PIOS_INCLUDE_DSM) +/* + * Spektrum/JR DSM USART + */ +#include + +static const struct pios_usart_cfg pios_usart_dsm_aux_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_aux_cfg = { + .bind = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_dsm_auxsbus_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = { + .bind = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { + .bind = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +#endif /* PIOS_INCLUDE_DSM */ + +#if defined(PIOS_INCLUDE_SBUS) +/* + * S.Bus USART + */ +#include + +static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = { + .regs = UART4, + .init = { + .USART_BaudRate = 100000, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_Even, + .USART_StopBits = USART_StopBits_2, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +static const struct pios_sbus_cfg pios_sbus_cfg = { + /* Inverter configuration */ + .inv = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .gpio_clk_func = RCC_AHB1PeriphClockCmd, + .gpio_clk_periph = RCC_AHB1Periph_GPIOB, + .gpio_inv_enable = Bit_SET, +}; + +#endif /* PIOS_INCLUDE_SBUS */ + +#if defined(PIOS_INCLUDE_COM) + +#include + +#endif /* PIOS_INCLUDE_COM */ + +#if defined(PIOS_INCLUDE_I2C) + +#include + +/* + * I2C Adapters + */ +void PIOS_I2C_mag_adapter_ev_irq_handler(void); +void PIOS_I2C_mag_adapter_er_irq_handler(void); +void I2C1_EV_IRQHandler() +__attribute__ ((alias("PIOS_I2C_mag_adapter_ev_irq_handler"))); +void I2C1_ER_IRQHandler() +__attribute__ ((alias("PIOS_I2C_mag_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { + .regs = I2C1, + .remap = GPIO_AF_I2C1, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_mag_adapter_id; +void PIOS_I2C_mag_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_adapter_id); +} + +void PIOS_I2C_mag_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_adapter_id); +} + + +void PIOS_I2C_flexiport_adapter_ev_irq_handler(void); +void PIOS_I2C_flexiport_adapter_er_irq_handler(void); +void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_ev_irq_handler"))); +void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = { + .regs = I2C2, + .remap = GPIO_AF_I2C2, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_flexiport_adapter_id; +void PIOS_I2C_flexiport_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexiport_adapter_id); +} + +void PIOS_I2C_flexiport_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexiport_adapter_id); +} + + +void PIOS_I2C_pressure_adapter_ev_irq_handler(void); +void PIOS_I2C_pressure_adapter_er_irq_handler(void); +void I2C3_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_ev_irq_handler"))); +void I2C3_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = { + .regs = I2C3, + .remap = GPIO_AF_I2C3, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 40000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .sda = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C3_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C3_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_pressure_adapter_id; +void PIOS_I2C_pressure_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id); +} + +void PIOS_I2C_pressure_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id); +} +#endif /* PIOS_INCLUDE_I2C */ + +#if defined(PIOS_INCLUDE_RTC) +/* + * Realtime Clock (RTC) + */ +#include + +void PIOS_RTC_IRQ_Handler (void); +void RTC_WKUP_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); +static const struct pios_rtc_cfg pios_rtc_main_cfg = { + .clksrc = RCC_RTCCLKSource_HSE_Div16, // Divide 8 Mhz crystal down to 1 + // For some reason it's acting like crystal is 16 Mhz. This clock is then divided + // by another 16 to give a nominal 62.5 khz clock + .prescaler = 100, // Every 100 cycles gives 625 Hz + .irq = { + .init = { + .NVIC_IRQChannel = RTC_WKUP_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +void PIOS_RTC_IRQ_Handler (void) +{ + PIOS_RTC_irq_handler (); +} + +#endif + +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_3_5_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; +static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_5_cfg = { + .timer = TIM5, + .time_base_init = &tim_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_9_cfg = { + .timer = TIM9, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_BRK_TIM9_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_10_cfg = { + .timer = TIM10, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_UP_TIM10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_11_cfg = { + .timer = TIM11, + .time_base_init = &tim_9_10_11_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_TRG_COM_TIM11_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_1_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_4_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +/** + * Pios servo configuration structures + */ +#include +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM9, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource5, + }, + .remap = GPIO_AF_TIM9, + }, + { + .timer = TIM9, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource6, + }, + .remap = GPIO_AF_TIM9, + }, + { + .timer = TIM11, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource9, + }, + .remap = GPIO_AF_TIM11, + }, + { + .timer = TIM10, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM10, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource2, + }, + .remap = GPIO_AF_TIM5, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource3, + }, + .remap = GPIO_AF_TIM5, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource0, + }, + .remap = GPIO_AF_TIM3, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource1, + }, + .remap = GPIO_AF_TIM3, + }, +}; + +const struct pios_servo_cfg pios_servo_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), +}; + + +/* + * PWM Inputs + */ +#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) +#include +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource15, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource14, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource13, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource12, + }, + .remap = GPIO_AF_TIM4, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource14, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource13, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource11, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource9, + }, + .remap = GPIO_AF_TIM1, + }, +}; + +const struct pios_pwm_cfg pios_pwm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), +}; +#endif + +/* + * PPM Input + */ +#if defined(PIOS_INCLUDE_PPM) +#include +static const struct pios_ppm_cfg pios_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + .TIM_Channel = TIM_Channel_2, + }, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, +}; + +#endif //PPM + +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "pios_gcsrcvr_priv.h" +#endif /* PIOS_INCLUDE_GCSRCVR */ + +#if defined(PIOS_INCLUDE_RCVR) +#include "pios_rcvr_priv.h" +#endif /* PIOS_INCLUDE_RCVR */ + +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" + +static const struct pios_usb_cfg pios_usb_main_cfg = { + .irq = { + .init = { + .NVIC_IRQChannel = OTG_FS_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 3, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_25MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + }, + } +}; + +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_cdc_priv.h" +#include "pios_usb_desc_hid_only_priv.h" +#include "pios_usbhook.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_COM_MSG) + +#include + +#endif /* PIOS_INCLUDE_COM_MSG */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; +#endif /* PIOS_INCLUDE_USB_HID */ + +#if defined(PIOS_INCLUDE_USB_CDC) +#include + +const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { + .ctrl_if = 1, + .ctrl_tx_ep = 2, + + .data_if = 2, + .data_rx_ep = 3, + .data_tx_ep = 3, +}; +#endif /* PIOS_INCLUDE_USB_CDC */ From b463e36d67be203866955390c53394019d66a539 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 12:24:13 -0500 Subject: [PATCH 379/508] Add revomini to the build system. --- Makefile | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/Makefile b/Makefile index 2087e7fc4..3cd0d3b90 100644 --- a/Makefile +++ b/Makefile @@ -654,7 +654,7 @@ all_$(1)_clean: $$(addsuffix _clean, $$(filter bu_$(1), $$(BU_TARGETS))) all_$(1)_clean: $$(addsuffix _clean, $$(filter ef_$(1), $$(EF_TARGETS))) endef -ALL_BOARDS := coptercontrol pipxtreme revolution simposix osd +ALL_BOARDS := coptercontrol pipxtreme revolution revomini simposix osd ALL_BOARDS_BU := coptercontrol pipxtreme simposix # SimPosix only builds on Linux so drop it from the list for @@ -674,6 +674,7 @@ endif coptercontrol_friendly := CopterControl pipxtreme_friendly := PipXtreme revolution_friendly := Revolution +revomini_friendly := RevoMini simposix_friendly := SimPosix osd_friendly := OSD @@ -681,13 +682,7 @@ osd_friendly := OSD coptercontrol_short := 'cc ' pipxtreme_short := 'pipx' revolution_short := 'revo' -simposix_short := 'posx' -osd_short := 'osd ' - -# Short hames of each board (used to display board name in parallel builds) -coptercontrol_short := 'cc ' -pipxtreme_short := 'pipx' -revolution_short := 'revo' +revomini_short := 'rm' simposix_short := 'posx' osd_short := 'osd ' From 05e2e24bcbf436c141494c0a956a98c934b8d74d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 12:38:44 -0500 Subject: [PATCH 380/508] Reconfigure the SPI ports. --- flight/RevoMini/Makefile | 1 - flight/RevoMini/System/inc/pios_config.h | 4 - flight/RevoMini/System/pios_board.c | 61 +--- flight/board_hw_defs/revomini/board_hw_defs.c | 325 ++---------------- 4 files changed, 40 insertions(+), 351 deletions(-) diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index 88d154ba5..7df49d2a7 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -55,7 +55,6 @@ MODULES += Altitude/revolution GPS FirmwareIAP MODULES += Airspeed/revolution MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += CameraStab -MODULES += OveroSync MODULES += Telemetry PYMODULES = #FlightPlan diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 4bb7be2a7..076fe1626 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -57,15 +57,12 @@ #define PIOS_INCLUDE_WDG /* Select the sensors to include */ -#define PIOS_INCLUDE_BMA180 #define PIOS_INCLUDE_HMC5883 #define PIOS_INCLUDE_MPU6000 #define PIOS_MPU6000_ACCEL -#define PIOS_INCLUDE_L3GD20 #define PIOS_INCLUDE_MS5611 #define PIOS_INCLUDE_ETASV3 //#define PIOS_INCLUDE_HCSR04 -#define PIOS_FLASH_ON_ACCEL /* true for second revo */ #define FLASH_FREERTOS /* Com systems to include */ #define PIOS_INCLUDE_COM @@ -79,7 +76,6 @@ #define PIOS_INCLUDE_GPS_UBX_PARSER #define PIOS_GPS_SETS_HOMELOCATION -#define PIOS_OVERO_SPI /* Supported receiver interfaces */ #define PIOS_INCLUDE_RCVR #define PIOS_INCLUDE_DSM diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index b9360bfef..8b7d43909 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -383,24 +383,18 @@ void PIOS_Board_Init(void) { PIOS_LED_Init(&pios_led_cfg); - /* Set up the SPI interface to the accelerometer*/ - if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { - PIOS_DEBUG_Assert(0); - } - - /* Set up the SPI interface to the gyro */ + /* Set up the SPI interface to the gyro/acelerometer */ if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { PIOS_DEBUG_Assert(0); } -#if !defined(PIOS_FLASH_ON_ACCEL) - /* Set up the SPI interface to the flash */ - if (PIOS_SPI_Init(&pios_spi_flash_id, &pios_spi_flash_cfg)) { + + /* Set up the SPI interface to the flash and rfm22b */ + if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) { PIOS_DEBUG_Assert(0); } - PIOS_Flash_Jedec_Init(pios_spi_flash_id, 0, &flash_m25p_cfg); -#else - PIOS_Flash_Jedec_Init(pios_spi_accel_id, 1, &flash_m25p_cfg); -#endif + + /* Connect flash to the approrpiate interface and configure it */ + PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 0, &flash_m25p_cfg); PIOS_FLASHFS_Init(&flashfs_m25p_cfg); /* Initialize UAVObject libraries */ @@ -780,29 +774,6 @@ void PIOS_Board_Init(void) { break; } -#if defined(PIOS_OVERO_SPI) - /* Set up the SPI based PIOS_COM interface to the overo */ - { - HwSettingsData hwSettings; - HwSettingsGet(&hwSettings); - if(hwSettings.OptionalModules[HWSETTINGS_OPTIONALMODULES_OVERO] == HWSETTINGS_OPTIONALMODULES_ENABLED) { - if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { - PIOS_DEBUG_Assert(0); - } - const uint32_t PACKET_SIZE = 1024; - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PACKET_SIZE); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, - rx_buffer, PACKET_SIZE, - tx_buffer, PACKET_SIZE)) { - PIOS_Assert(0); - } - } - } - -#endif #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); @@ -856,25 +827,9 @@ void PIOS_Board_Init(void) { PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id); #endif - switch(bdinfo->board_rev) { - case 0x01: -#if defined(PIOS_INCLUDE_L3GD20) - PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg); - PIOS_Assert(PIOS_L3GD20_Test() == 0); -#endif -#if defined(PIOS_INCLUDE_BMA180) - PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg); - PIOS_Assert(PIOS_BMA180_Test() == 0); -#endif - break; - case 0x02: #if defined(PIOS_INCLUDE_MPU6000) - PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg); + PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg); #endif - break; - default: - PIOS_DEBUG_Assert(0); - } } diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index b54dd119d..6269a76c5 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -35,21 +35,9 @@ static const struct pios_led pios_leds[] = { [PIOS_LED_HEARTBEAT] = { .pin = { - .gpio = GPIOE, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - }, - [PIOS_LED_ALARM] = { - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_3, + .GPIO_Pin = GPIO_Pin_12, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, @@ -73,13 +61,15 @@ const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revisio #if defined(PIOS_INCLUDE_SPI) #include -/* SPI1 Interface - * - Used for BMA180 accelerometer + +/* + * SPI1 Interface + * Used for MPU6000 gyro and accelerometer */ -void PIOS_SPI_accel_irq_handler(void); -void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); -void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); -static const struct pios_spi_cfg pios_spi_accel_cfg = { +void PIOS_SPI_gyro_irq_handler(void); +void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); +static const struct pios_spi_cfg pios_spi_gyro_cfg = { .regs = SPI1, .remap = GPIO_AF_SPI1, .init = { @@ -172,7 +162,7 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = { .GPIO_PuPd = GPIO_PuPd_UP }, }, - .slave_count = 2, + .slave_count = 1, .ssel = { { .gpio = GPIOA, .init = { @@ -181,142 +171,11 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = { .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP - } }, - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, + } } } }; -static uint32_t pios_spi_accel_id; -void PIOS_SPI_accel_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_accel_id); -} - - -/* SPI2 Interface - * - Used for gyro communications - */ -void PIOS_SPI_GYRO_irq_handler(void); -void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); -void DMA1_Stream4_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); -static const struct pios_spi_cfg pios_spi_gyro_cfg = { - .regs = SPI2, - .remap = GPIO_AF_SPI2, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case RX) - .flags = (DMA_IT_TCIF3 | DMA_IT_TEIF3 | DMA_IT_HTIF3), - .init = { - .NVIC_IRQChannel = DMA1_Stream3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Stream3, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream4, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - } }, -}; - -uint32_t pios_spi_gyro_id; +static uint32_t pios_spi_gyro_id; void PIOS_SPI_gyro_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ @@ -324,14 +183,14 @@ void PIOS_SPI_gyro_irq_handler(void) } -#if !defined(PIOS_FLASH_ON_ACCEL) -/* SPI3 Interface - * - Used for flash communications +/* + * SPI3 Interface + * Used for Flash and the RFM22B */ -void PIOS_SPI_flash_irq_handler(void); -void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); -void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); -static const struct pios_spi_cfg pios_spi_flash_cfg = { +void PIOS_SPI_telem_flash_irq_handler(void); +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_telem_flash_irq_handler"))); +void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_telem_flash_irq_handler"))); +static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, .init = { @@ -427,132 +286,16 @@ static const struct pios_spi_cfg pios_spi_flash_cfg = { }, }, .slave_count = 1, - .ssel = { { - .gpio = GPIOD, + .ssel = { { // Flash + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_2, + .GPIO_Pin = GPIO_Pin_3, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP - }, - } }, -}; - -uint32_t pios_spi_flash_id; -void PIOS_SPI_flash_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_flash_id); -} -#endif /* PIOS_FLASH_ON_ACCEL */ - -#endif /* PIOS_INCLUDE_SPI */ - -#if defined(PIOS_OVERO_SPI) -/* SPI3 Interface - * - Used for flash communications - */ -#include -void PIOS_OVERO_irq_handler(void); -void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); -static const struct pios_overo_cfg pios_overo_cfg = { - .regs = SPI3, - .remap = GPIO_AF_SPI3, - .init = { - .SPI_Mode = SPI_Mode_Slave, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Hard, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case TX) - .flags = (DMA_IT_TCIF7), - .init = { - .NVIC_IRQChannel = DMA1_Stream7_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Stream0, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream7, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { + } }, + { // RFM22b .gpio = GPIOA, .init = { .GPIO_Pin = GPIO_Pin_15, @@ -560,22 +303,18 @@ static const struct pios_overo_cfg pios_overo_cfg = { .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP - }, - } }, + } }, + }, }; -uint32_t pios_overo_id = 0; -void PIOS_OVERO_irq_handler(void) + +uint32_t pios_spi_telem_flash_id; +void PIOS_SPI_telem_flash_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_OVERO_DMA_irq_handler(pios_overo_id); + PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id); } -#else - -#endif /* PIOS_OVERO_SPI */ - - - +#endif /* PIOS_INCLUDE_SPI */ #include From b9050809cc4bef8bf7cadf3fdaaca96eb571dbb7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 12:57:50 -0500 Subject: [PATCH 381/508] Add a board info file for revo mini. However it was to remap the define MAINADAPTER for the HMC5883 driver which needs rewriting not to need this. --- flight/PiOS/Boards/STM32F4xx_RevoMini.h | 270 ++++++++++++++++++++++++ flight/PiOS/Boards/pios_board.h | 2 + make/boards/revomini/board-info.mk | 27 +++ 3 files changed, 299 insertions(+) create mode 100644 flight/PiOS/Boards/STM32F4xx_RevoMini.h create mode 100644 make/boards/revomini/board-info.mk diff --git a/flight/PiOS/Boards/STM32F4xx_RevoMini.h b/flight/PiOS/Boards/STM32F4xx_RevoMini.h new file mode 100644 index 000000000..5a49f1fbb --- /dev/null +++ b/flight/PiOS/Boards/STM32F4xx_RevoMini.h @@ -0,0 +1,270 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef STM3210E_INS_H_ +#define STM3210E_INS_H_ + +#include + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | | | | +TIM2 | --------------- PIOS_DELAY ----------------- +TIM3 | | | | +TIM4 | | | | +TIM5 | | | | +TIM6 | | | | +TIM7 | | | | +TIM8 | | | | +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - SPI1 RX */ +/* Channel 3 - SPI1 TX */ +/* Channel 4 - SPI2 RX */ +/* Channel 5 - SPI2 TX */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE true +#define BOARD_WRITABLE true +#define MAX_DEL_RETRYS 3 + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 + +//------------------------ +// PIOS_SPI +// See also pios_board.c +//------------------------ +#define PIOS_SPI_MAX_DEVS 3 + +//------------------------ +// PIOS_WDG +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER RTC_BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_ATTITUDE 0x0004 +#define PIOS_WDG_MANUAL 0x0008 +#define PIOS_WDG_SENSORS 0x0010 + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 3 +extern uint32_t pios_i2c_mag_pressure_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id) +extern uint32_t pios_i2c_flexiport_adapter_id; +#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id) +#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER) + +//------------------------- +// PIOS_USART +// +// See also pios_board.c +//------------------------- +#define PIOS_USART_MAX_DEVS 5 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 4 +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_bridge_id; +extern uint32_t pios_com_vcp_id; +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_BRIDGE (pios_com_bridge_id) +#define PIOS_COM_VCP (pios_com_vcp_id) +#define PIOS_COM_DEBUG PIOS_COM_AUX + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 80 +#define PIOS_TELEM_STACK_SIZE 624 + +//------------------------- +// System Settings +// +// See also System_stm32f4xx.c +//------------------------- +//These macros are deprecated +//please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below +//#define PIOS_MASTER_CLOCK +//#define PIOS_PERIPHERAL_CLOCK +//#define PIOS_PERIPHERAL_CLOCK + +#define PIOS_SYSCLK 168000000 +// Peripherals that belongs to APB1 are: +// DAC |PWR |CAN1,2 +// I2C1,2,3 |UART4,5 |USART3,2 +// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 +// I2S2Ext |IWDG |WWDG +// RTC/BKP reg +// TIM2,3,4,5,6,7,12,13,14 + +// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) +// Default APB1 Prescaler = 4 +#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) + +// Peripherals belonging to APB2 +// SDIO |EXTI |SYSCFG |SPI1 +// ADC1,2,3 +// USART1,6 +// TIM1,8,9,10,11 +// +// Default APB2 Prescaler = 2 +// +#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK + + +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 12 + +//------------------------- +// Receiver PWM input +//------------------------- +#define PIOS_PWM_MAX_DEVS 1 +#define PIOS_PWM_NUM_INPUTS 8 + +//------------------------- +// Receiver SPEKTRUM input +//------------------------- +#define PIOS_SPEKTRUM_MAX_DEVS 2 +#define PIOS_SPEKTRUM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 1 +#define PIOS_SBUS_NUM_INPUTS (16+2) + +//------------------------- +// Receiver DSM input +//------------------------- +#define PIOS_DSM_MAX_DEVS 2 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 6 + +//------------------------- +// ADC +// PIOS_ADC_PinGet(0) = Current sensor +// PIOS_ADC_PinGet(1) = Voltage sensor +// PIOS_ADC_PinGet(4) = VREF +// PIOS_ADC_PinGet(5) = Temperature sensor +//------------------------- +#define PIOS_DMA_PIN_CONFIG \ +{ \ + {GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ + {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ + {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ + {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ + {GPIOC, GPIO_Pin_2, ADC_Channel_12} \ +} + +/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ +/* which is annoying because this then determines the rate at which we generate buffer turnover events */ +/* the objective here is to get enough buffer space to support 100Hz averaging rate */ +#define PIOS_ADC_NUM_CHANNELS 4 +#define PIOS_ADC_MAX_OVERSAMPLING 2 +#define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_VOLTAGE_SCALE 3.30/4096.0 + +//------------------------- +// USB +//------------------------- +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ +#define PIOS_USB_HID_MAX_DEVS 1 + +#endif /* STM3210E_INS_H_ */ +/** + * @} + * @} + */ diff --git a/flight/PiOS/Boards/pios_board.h b/flight/PiOS/Boards/pios_board.h index 1b2588bc5..1a3c63119 100644 --- a/flight/PiOS/Boards/pios_board.h +++ b/flight/PiOS/Boards/pios_board.h @@ -13,6 +13,8 @@ #include "STM32F2xx_INS.h" #elif USE_STM32F4xx_OP #include "STM32F4xx_Revolution.h" +#elif USE_STM32F4xx_RM +#include "STM32F4xx_RevoMini.h" #else #error Board definition has not been provided. #endif diff --git a/make/boards/revomini/board-info.mk b/make/boards/revomini/board-info.mk new file mode 100644 index 000000000..33fdb0591 --- /dev/null +++ b/make/boards/revomini/board-info.mk @@ -0,0 +1,27 @@ +BOARD_TYPE := 0x09 +BOARD_REVISION := 0x02 +BOOTLOADER_VERSION := 0x01 +HW_TYPE := 0x00 + +MCU := cortex-m4 +CHIP := STM32F405RGT +BOARD := STM32F4xx_RM +MODEL := HD +MODEL_SUFFIX := + +OPENOCD_JTAG_CONFIG := stlink-v2.cfg +OPENOCD_CONFIG := stm32f4xx.stlink.cfg + +# Note: These must match the values in link_$(BOARD)_memory.ld +BL_BANK_BASE := 0x08000000 # Start of bootloader flash +BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region + +# Leave the remaining 16KB and 64KB sectors for other uses + +FW_BANK_BASE := 0x08020000 # Start of firmware flash +FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE + +FW_DESC_SIZE := 0x00000064 + +OSCILLATOR_FREQ := 8000000 +SYSCLK_FREQ := 168000000 From ce5ef7edf353b005635ccbc663a45e1cf1f415ab Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 13:19:23 -0500 Subject: [PATCH 382/508] Update the serial ports and receiver and servo ports --- flight/RevoMini/System/pios_board.c | 147 +--- flight/board_hw_defs/revomini/board_hw_defs.c | 774 ++++-------------- 2 files changed, 169 insertions(+), 752 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 8b7d43909..7d6aab68d 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -533,7 +533,7 @@ void PIOS_Board_Init(void) { uint8_t hwsettings_DSMxBind; HwSettingsDSMxBindGet(&hwsettings_DSMxBind); - /* Configure Telemetry port */ + /* Configure main USART port */ uint8_t hwsettings_rv_telemetryport; HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport); @@ -541,149 +541,18 @@ void PIOS_Board_Init(void) { case HWSETTINGS_RV_TELEMETRYPORT_DISABLED: break; case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); break; case HWSETTINGS_RV_TELEMETRYPORT_COMAUX: - PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); break; case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; } /* hwsettings_rv_telemetryport */ - /* Configure GPS port */ - uint8_t hwsettings_rv_gpsport; - HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport); - switch (hwsettings_rv_gpsport){ - case HWSETTINGS_RV_GPSPORT_DISABLED: - break; - - case HWSETTINGS_RV_GPSPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - - case HWSETTINGS_RV_GPSPORT_GPS: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); - break; - - case HWSETTINGS_RV_GPSPORT_COMAUX: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); - break; - - case HWSETTINGS_RV_GPSPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - }/* hwsettings_rv_gpsport */ - - /* Configure AUXPort */ - uint8_t hwsettings_rv_auxport; - HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport); - - switch (hwsettings_rv_auxport) { - case HWSETTINGS_RV_AUXPORT_DISABLED: - break; - - case HWSETTINGS_RV_AUXPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - - case HWSETTINGS_RV_AUXPORT_DSM2: - case HWSETTINGS_RV_AUXPORT_DSMX10BIT: - case HWSETTINGS_RV_AUXPORT_DSMX11BIT: - { - enum pios_dsm_proto proto; - switch (hwsettings_rv_auxport) { - case HWSETTINGS_RV_AUXPORT_DSM2: - proto = PIOS_DSM_PROTO_DSM2; - break; - case HWSETTINGS_RV_AUXPORT_DSMX10BIT: - proto = PIOS_DSM_PROTO_DSMX10BIT; - break; - case HWSETTINGS_RV_AUXPORT_DSMX11BIT: - proto = PIOS_DSM_PROTO_DSMX11BIT; - break; - default: - PIOS_Assert(0); - break; - } - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_aux_cfg, &pios_dsm_aux_cfg, - &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); - } - break; - case HWSETTINGS_RV_AUXPORT_COMAUX: - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); - break; - case HWSETTINGS_RV_AUXPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - } /* hwsettings_rv_auxport */ - /* Configure AUXSbusPort */ - //TODO: ensure that the serial invertion pin is setted correctly - uint8_t hwsettings_rv_auxsbusport; - HwSettingsRV_AuxSBusPortGet(&hwsettings_rv_auxsbusport); - - switch (hwsettings_rv_auxsbusport) { - case HWSETTINGS_RV_AUXSBUSPORT_DISABLED: - break; - case HWSETTINGS_RV_AUXSBUSPORT_SBUS: -#ifdef PIOS_INCLUDE_SBUS - { - uint32_t pios_usart_sbus_id; - if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_sbus_id; - if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { - PIOS_Assert(0); - } - - uint32_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; - - } -#endif /* PIOS_INCLUDE_SBUS */ - break; - - case HWSETTINGS_RV_AUXSBUSPORT_DSM2: - case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: - case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: - { - enum pios_dsm_proto proto; - switch (hwsettings_rv_auxsbusport) { - case HWSETTINGS_RV_AUXSBUSPORT_DSM2: - proto = PIOS_DSM_PROTO_DSM2; - break; - case HWSETTINGS_RV_AUXSBUSPORT_DSMX10BIT: - proto = PIOS_DSM_PROTO_DSMX10BIT; - break; - case HWSETTINGS_RV_AUXSBUSPORT_DSMX11BIT: - proto = PIOS_DSM_PROTO_DSMX11BIT; - break; - default: - PIOS_Assert(0); - break; - } - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_auxsbus_cfg, &pios_dsm_auxsbus_cfg, - &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); - } - break; - case HWSETTINGS_RV_AUXSBUSPORT_COMAUX: - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); - break; - case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - } /* hwsettings_rv_auxport */ - /* Configure FlexiPort */ - uint8_t hwsettings_rv_flexiport; HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport); @@ -805,11 +674,7 @@ void PIOS_Board_Init(void) { PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); #endif - if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - - if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) { + if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) { PIOS_DEBUG_Assert(0); } @@ -824,7 +689,7 @@ void PIOS_Board_Init(void) { #endif #if defined(PIOS_INCLUDE_MS5611) - PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id); + PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_mag_pressure_adapter_id); #endif #if defined(PIOS_INCLUDE_MPU6000) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 6269a76c5..6f2873b05 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -319,58 +319,11 @@ void PIOS_SPI_telem_flash_irq_handler(void) #include #ifdef PIOS_INCLUDE_COM_TELEM -/* - * Telemetry on main USART - */ -static const struct pios_usart_cfg pios_usart_telem_cfg = { - .regs = USART2, - .remap = GPIO_AF_USART2, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; -#endif /* PIOS_COM_TELEM */ - -#ifdef PIOS_INCLUDE_GPS /* - * GPS USART + * MAIN USART */ -static const struct pios_usart_cfg pios_usart_gps_cfg = { +static const struct pios_usart_cfg pios_usart_main_cfg = { .regs = USART1, .remap = GPIO_AF_USART1, .init = { @@ -412,103 +365,7 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = { }, }; -#endif /* PIOS_INCLUDE_GPS */ -#ifdef PIOS_INCLUDE_COM_AUX -/* - * AUX USART (UART label on rev2) - */ -static const struct pios_usart_cfg pios_usart_aux_cfg = { - .regs = USART6, - .remap = GPIO_AF_USART6, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART6_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -#endif /* PIOS_COM_AUX */ - -#ifdef PIOS_INCLUDE_COM_AUXSBUS -/* - * AUX USART SBUS ( UART/ S Bus label on rev2) - */ -static const struct pios_usart_cfg pios_usart_auxsbus_cfg = { - .regs = UART4, - .remap = GPIO_AF_UART4, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = UART4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -#endif /* PIOS_INCLUDE_COM_AUXSBUS */ #ifdef PIOS_INCLUDE_COM_FLEXI /* @@ -558,120 +415,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = { #endif /* PIOS_INCLUDE_COM_FLEXI */ -#if defined(PIOS_INCLUDE_DSM) -/* - * Spektrum/JR DSM USART - */ -#include - -static const struct pios_usart_cfg pios_usart_dsm_aux_cfg = { - .regs = USART6, - .remap = GPIO_AF_USART6, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART6_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_aux_cfg = { - .bind = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_usart_cfg pios_usart_dsm_auxsbus_cfg = { - .regs = UART4, - .remap = GPIO_AF_UART4, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = UART4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = { - .bind = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - +#include "pios_dsm_priv.h" static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { .regs = USART3, .remap = GPIO_AF_USART3, @@ -728,70 +472,6 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { #endif /* PIOS_INCLUDE_DSM */ -#if defined(PIOS_INCLUDE_SBUS) -/* - * S.Bus USART - */ -#include - -static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = { - .regs = UART4, - .init = { - .USART_BaudRate = 100000, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_Even, - .USART_StopBits = USART_StopBits_2, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = UART4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_sbus_cfg pios_sbus_cfg = { - /* Inverter configuration */ - .inv = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - .gpio_clk_func = RCC_AHB1PeriphClockCmd, - .gpio_clk_periph = RCC_AHB1Periph_GPIOB, - .gpio_inv_enable = Bit_SET, -}; - -#endif /* PIOS_INCLUDE_SBUS */ - #if defined(PIOS_INCLUDE_COM) #include @@ -805,14 +485,14 @@ static const struct pios_sbus_cfg pios_sbus_cfg = { /* * I2C Adapters */ -void PIOS_I2C_mag_adapter_ev_irq_handler(void); -void PIOS_I2C_mag_adapter_er_irq_handler(void); +void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void); +void PIOS_I2C_mag_pressureadapter_er_irq_handler(void); void I2C1_EV_IRQHandler() -__attribute__ ((alias("PIOS_I2C_mag_adapter_ev_irq_handler"))); + __attribute__ ((alias("PIOS_I2C_mag_pressure_adapter_ev_irq_handler"))); void I2C1_ER_IRQHandler() -__attribute__ ((alias("PIOS_I2C_mag_adapter_er_irq_handler"))); + __attribute__ ((alias("PIOS_I2C_mag_pressure_adapter_er_irq_handler"))); -static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { +static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = { .regs = I2C1, .remap = GPIO_AF_I2C1, .init = { @@ -827,7 +507,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { .scl = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_6, + .GPIO_Pin = GPIO_Pin_8, .GPIO_Mode = GPIO_Mode_AF, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_OType = GPIO_OType_OD, @@ -837,7 +517,7 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { .sda = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_7, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Mode = GPIO_Mode_AF, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_OType = GPIO_OType_OD, @@ -864,17 +544,17 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { }, }; -uint32_t pios_i2c_mag_adapter_id; -void PIOS_I2C_mag_adapter_ev_irq_handler(void) +uint32_t pios_i2c_mag_pressure_adapter_id; +void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_adapter_id); + PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_pressure_adapter_id); } -void PIOS_I2C_mag_adapter_er_irq_handler(void) +void PIOS_I2C_mag_pressure_adapter_er_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_adapter_id); + PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_pressure_adapter_id); } @@ -951,73 +631,7 @@ void PIOS_I2C_flexiport_adapter_er_irq_handler(void) void PIOS_I2C_pressure_adapter_ev_irq_handler(void); void PIOS_I2C_pressure_adapter_er_irq_handler(void); -void I2C3_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_ev_irq_handler"))); -void I2C3_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_er_irq_handler"))); -static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = { - .regs = I2C3, - .remap = GPIO_AF_I2C3, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 40000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C3_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C3_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_pressure_adapter_id; -void PIOS_I2C_pressure_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id); -} - -void PIOS_I2C_pressure_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id); -} #endif /* PIOS_INCLUDE_I2C */ #if defined(PIOS_INCLUDE_RTC) @@ -1177,105 +791,10 @@ static const struct pios_tim_clock_cfg tim_4_cfg = { /** * Pios servo configuration structures + * Using TIM3, TIM9, TIM2, TIM5 */ #include static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { - { - .timer = TIM9, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource5, - }, - .remap = GPIO_AF_TIM9, - }, - { - .timer = TIM9, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource6, - }, - .remap = GPIO_AF_TIM9, - }, - { - .timer = TIM11, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource9, - }, - .remap = GPIO_AF_TIM11, - }, - { - .timer = TIM10, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource8, - }, - .remap = GPIO_AF_TIM10, - }, - { - .timer = TIM5, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource2, - }, - .remap = GPIO_AF_TIM5, - }, - { - .timer = TIM5, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource3, - }, - .remap = GPIO_AF_TIM5, - }, { .timer = TIM3, .timer_chan = TIM_Channel_3, @@ -1308,6 +827,70 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { }, .remap = GPIO_AF_TIM3, }, + { + .timer = TIM9, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource3, + }, + .remap = GPIO_AF_TIM9, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource2, + }, + .remap = GPIO_AF_TIM2, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource1, + }, + .remap = GPIO_AF_TIM5, + }, + { + .timer = TIM5, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource1, + }, + .remap = GPIO_AF_TIM5, + }, }; const struct pios_servo_cfg pios_servo_cfg = { @@ -1328,127 +911,32 @@ const struct pios_servo_cfg pios_servo_cfg = { /* * PWM Inputs + * TIM1, TIM8, TIM12 */ #if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) #include static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { - { - .timer = TIM4, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource15, - }, - .remap = GPIO_AF_TIM4, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource14, - }, - .remap = GPIO_AF_TIM4, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource13, - }, - .remap = GPIO_AF_TIM4, - }, - { - .timer = TIM4, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource12, - }, - .remap = GPIO_AF_TIM4, - }, - { - .timer = TIM1, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource14, - }, - .remap = GPIO_AF_TIM1, - }, - { - .timer = TIM1, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource13, - }, - .remap = GPIO_AF_TIM1, - }, - { - .timer = TIM1, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOE, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource11, - }, - .remap = GPIO_AF_TIM1, - }, { .timer = TIM1, .timer_chan = TIM_Channel_1, .pin = { - .gpio = GPIOE, + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM1, + }, + { + .timer = TIM8, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOC, .init = { .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, @@ -1458,7 +946,71 @@ static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { }, .pin_source = GPIO_PinSource9, }, - .remap = GPIO_AF_TIM1, + .remap = GPIO_AF_TIM8, + }, + { + .timer = TIM8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM8, + }, + { + .timer = TIM8, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource7, + }, + .remap = GPIO_AF_TIM8, + }, + { + .timer = TIM8, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource6, + }, + .remap = GPIO_AF_TIM8, + }, + { + .timer = TIM12, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource15, + }, + .remap = GPIO_AF_TIM12, }, }; From fad32dcc29364d654fe6614683eac15a49bbfdea Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 24 Aug 2012 19:25:02 -0700 Subject: [PATCH 383/508] Split out the PipX radio interface from RadioComBridge module to a separate Radio module. Now the RadioComBridge module just routes messages between the com ports and handles sending/receiving the PipX UAVOs. --- flight/Libraries/inc/packet_handler.h | 12 +- flight/Libraries/packet_handler.c | 70 ++- flight/Modules/Radio/inc/radio.h | 39 ++ flight/Modules/Radio/radio.c | 539 ++++++++++++++++++ .../Modules/RadioComBridge/RadioComBridge.c | 409 ++----------- .../PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h | 38 +- flight/PiOS/Common/pios_rfm22b.c | 439 +++----------- flight/PiOS/inc/pios_rfm22b.h | 2 + flight/PiOS/inc/pios_rfm22b_priv.h | 2 + flight/PipXtreme/Makefile | 2 +- flight/PipXtreme/System/inc/pios_config.h | 5 + flight/PipXtreme/System/pios_board.c | 110 +--- .../board_hw_defs/pipxtreme/board_hw_defs.c | 64 ++- 13 files changed, 862 insertions(+), 869 deletions(-) create mode 100644 flight/Modules/Radio/inc/radio.h create mode 100644 flight/Modules/Radio/radio.c diff --git a/flight/Libraries/inc/packet_handler.h b/flight/Libraries/inc/packet_handler.h index 1e9f60807..1a4785842 100644 --- a/flight/Libraries/inc/packet_handler.h +++ b/flight/Libraries/inc/packet_handler.h @@ -30,6 +30,9 @@ #ifndef __PACKET_HANDLER_H__ #define __PACKET_HANDLER_H__ +#include +#include + // Public defines / macros #define PHPacketSize(p) ((uint8_t*)(p->data) + p->header.data_size - (uint8_t*)p) #define PHPacketSizeECC(p) ((uint8_t*)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t*)p) @@ -71,7 +74,7 @@ typedef struct { #define PH_PPM_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) typedef struct { PHPacketHeader header; - uint16_t channels[PIOS_RCVR_MAX_CHANNELS]; + uint16_t channels[GCSRECEIVER_CHANNEL_NUMELEM]; uint8_t ecc[RS_ECC_NPARITY]; } PHPpmPacket, *PHPpmPacketHandle; @@ -87,8 +90,10 @@ typedef struct { } PHStatusPacket, *PHStatusPacketHandle; typedef struct { - uint8_t winSize; - uint16_t maxConnections; + uint32_t default_destination_id; + uint32_t source_id; + uint16_t max_connections; + uint8_t win_size; } PacketHandlerConfig; typedef int32_t (*PHOutputStream)(PHPacketHandle packet); @@ -110,6 +115,7 @@ void PHReleaseRXPacket(PHInstHandle h, PHPacketHandle p); PHPacketHandle PHGetTXPacket(PHInstHandle h); void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p); uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p); +uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len); int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len); uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error); diff --git a/flight/Libraries/packet_handler.c b/flight/Libraries/packet_handler.c index f4e8e28d7..c417371d7 100644 --- a/flight/Libraries/packet_handler.c +++ b/flight/Libraries/packet_handler.c @@ -44,7 +44,6 @@ typedef struct { uint8_t rx_win_start; uint8_t rx_win_end; uint16_t tx_seq_id; - PHOutputStream stream; xSemaphoreHandle lock; PHOutputStream output_stream; PHDataHandler data_handler; @@ -75,13 +74,13 @@ PHInstHandle PHInitialize(PacketHandlerConfig *cfg) data->tx_seq_id = 0; // Allocate the packet windows - data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize); - data->rx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize); + data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.win_size); + data->rx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.win_size); // Initialize the windows data->tx_win_start = data->tx_win_end = 0; data->rx_win_start = data->rx_win_end = 0; - for (uint8_t i = 0; i < data->cfg.winSize; ++i) + for (uint8_t i = 0; i < data->cfg.win_size; ++i) { data->tx_packets[i].header.type = PACKET_TYPE_NONE; data->rx_packets[i].header.type = PACKET_TYPE_NONE; @@ -93,6 +92,12 @@ PHInstHandle PHInitialize(PacketHandlerConfig *cfg) // Initialize the ECC library. initialize_ecc(); + // Initialize the handlers + data->output_stream = 0; + data->data_handler = 0; + data->status_handler = 0; + data->ppm_handler = 0; + // Return the structure. return (PHInstHandle)data; } @@ -172,7 +177,7 @@ PHPacketHandle PHGetTXPacket(PHInstHandle h) // Find a free packet. PHPacketHandle p = NULL; - for (uint8_t i = 0; i < data->cfg.winSize; ++i) + for (uint8_t i = 0; i < data->cfg.win_size; ++i) if (data->tx_packets[i].header.type == PACKET_TYPE_NONE) { p = data->tx_packets + i; @@ -205,7 +210,7 @@ void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p) // If this packet is at the start of the window, increment the start index. while ((data->tx_win_start != data->tx_win_end) && (data->tx_packets[data->tx_win_start].header.type == PACKET_TYPE_NONE)) - data->tx_win_start = (data->tx_win_start + 1) % data->cfg.winSize; + data->tx_win_start = (data->tx_win_start + 1) % data->cfg.win_size; // Release lock xSemaphoreGiveRecursive(data->lock); @@ -226,7 +231,7 @@ PHPacketHandle PHGetRXPacket(PHInstHandle h) // Find a free packet. PHPacketHandle p = NULL; - for (uint8_t i = 0; i < data->cfg.winSize; ++i) + for (uint8_t i = 0; i < data->cfg.win_size; ++i) if (data->rx_packets[i].header.type == PACKET_TYPE_NONE) { p = data->rx_packets + i; @@ -259,7 +264,7 @@ void PHReleaseRXPacket(PHInstHandle h, PHPacketHandle p) // If this packet is at the start of the window, increment the start index. while ((data->rx_win_start != data->rx_win_end) && (data->rx_packets[data->rx_win_start].header.type == PACKET_TYPE_NONE)) - data->rx_win_start = (data->rx_win_start + 1) % data->cfg.winSize; + data->rx_win_start = (data->rx_win_start + 1) % data->cfg.win_size; // Release lock xSemaphoreGiveRecursive(data->lock); @@ -280,19 +285,39 @@ uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p) if (!PHLTransmitPacket(data, p)) return 0; - // If this packet doesn't require an ACK, remove it from the TX window. - switch (p->header.type) { - case PACKET_TYPE_READY: - case PACKET_TYPE_NOTREADY: - case PACKET_TYPE_DATA: - case PACKET_TYPE_PPM: - PHReleaseTXPacket(h, p); - break; - } - return 1; } +/** + * Transmit a packet of data. + * \param[in] h The packet handler instance data pointer. + * \param[in] p A pointer to the data buffer. + * \param[in] len The length of the data buffer. + * \return 1 Success + * \return 0 Failure + */ +uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len) +{ + PHPacketDataHandle data = (PHPacketDataHandle)h; + + // Get a packet from the packet handler. + PHPacketHandle p = PHGetTXPacket(pios_packet_handler); + if (!p) + return 0; + + // Initialize the packet. + p->header.destination_id = data->cfg.default_destination_id; + p->header.source_id = data->cfg.source_id; + p->header.type = PACKET_TYPE_DATA; + p->header.data_size = len; + + // Copy the data into the packet. + memcpy(p->data, buf, len); + + // Send the packet. + return PHLTransmitPacket(data, p); +} + /** * Verify that a buffer contains a valid packet. * \param[in] h The packet handler instance data pointer. @@ -380,11 +405,11 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error) { // Find the packet ID in the TX buffer, and free it. unsigned int i = 0; - for (unsigned int i = 0; i < data->cfg.winSize; ++i) + for (unsigned int i = 0; i < data->cfg.win_size; ++i) if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) PHReleaseTXPacket(h, data->tx_packets + i); #ifdef DEBUG_LEVEL - if (i == data->cfg.winSize) + if (i == data->cfg.win_size) DEBUG_PRINTF(1, "Error finding acked packet to release\n\r"); #endif } @@ -394,11 +419,11 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error) { // Resend the packet. unsigned int i = 0; - for ( ; i < data->cfg.winSize; ++i) + for ( ; i < data->cfg.win_size; ++i) if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) PHLTransmitPacket(data, data->tx_packets + i); #ifdef DEBUG_LEVEL - if (i == data->cfg.winSize) + if (i == data->cfg.win_size) DEBUG_PRINTF(1, "Error finding acked packet to NACK\n\r"); DEBUG_PRINTF(1, "Resending after NACK\n\r"); #endif @@ -455,6 +480,7 @@ static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p) encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); // Transmit the packet using the output stream. + p->header.source_id = data->cfg.source_id; if(data->output_stream(p) == -1) return 0; diff --git a/flight/Modules/Radio/inc/radio.h b/flight/Modules/Radio/inc/radio.h new file mode 100644 index 000000000..58102e061 --- /dev/null +++ b/flight/Modules/Radio/inc/radio.h @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Radio Input / Output Module + * @brief Read and Write packets from/to a radio device. + * @{ + * + * @file radio.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Include file of the radio module. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef RADIOMODULE_H +#define RADIOMODULE_H + +#endif // RADIOMODULE_H + +/** + * @} + * @} + */ diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c new file mode 100644 index 000000000..6df334fae --- /dev/null +++ b/flight/Modules/Radio/radio.c @@ -0,0 +1,539 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Radio Input / Output Module + * @brief Read and Write packets from/to a radio device. + * @{ + * + * @file radio.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Bridges selected Com Port to the COM VCP emulated serial port + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// **************** +// Private constants + +#define STACK_SIZE_BYTES 150 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 2) +#define PACKET_QUEUE_SIZE PIOS_PH_WIN_SIZE +#define MAX_PORT_DELAY 200 +#define STATS_UPDATE_PERIOD_MS 500 +#define RADIOSTATS_UPDATE_PERIOD_MS 250 +#define MAX_LOST_CONTACT_TIME 4 + +#ifndef LINK_LED_ON +#define LINK_LED_ON +#define LINK_LED_OFF +#endif + +// **************** +// Private types + +typedef struct { + uint32_t pairID; + uint16_t retries; + uint16_t errors; + uint16_t uavtalk_errors; + uint16_t resets; + uint16_t dropped; + int8_t rssi; + uint8_t lastContact; +} PairStats; + +typedef struct { + + // The task handles. + xTaskHandle radioReceiveTaskHandle; + xTaskHandle radioStatusTaskHandle; + xTaskHandle sendPacketTaskHandle; + + // Queue handles. + xQueueHandle radioPacketQueue; + + // Error statistics. + uint32_t radioTxErrors; + uint32_t radioRxErrors; + uint32_t packetErrors; + uint16_t txBytes; + uint16_t rxBytes; + + // External error statistics + uint32_t droppedPackets; + uint32_t comTxRetries; + uint32_t UAVTalkErrors; + + // The destination ID + uint32_t destination_id; + + // Track other radios that are in range. + PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM]; + + // The RSSI of the last packet received. + int8_t RSSI; + +} RadioData; + +// **************** +// Private functions + +static void radioReceiveTask(void *parameters); +static void radioStatusTask(void *parameters); +static void sendPacketTask(void *parameters); +static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc); +static int32_t transmitPacket(PHPacketHandle packet); +static void PPMHandler(uint16_t *channels); + +// **************** +// Private variables + +static RadioData *data = 0; + +// **************** +// Global variables +uint32_t pios_rfm22b_id = 0; +uint32_t pios_com_rfm22b_id = 0; +uint32_t pios_packet_handler = 0; +extern struct pios_rfm22b_cfg pios_rfm22b_cfg; + + +/** + * Start the module + * \return -1 if initialisation failed + * \return 0 on success + */ +static int32_t RadioStart(void) +{ + if (!data) + return -1; + + // Start the tasks. + xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle)); + xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); + xTaskCreate(sendPacketTask, (signed char *)"SendPacket", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle)); + + // Register the watchdog timers. +#ifdef PIOS_WDG_RADIORECEIVE + PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE); +#endif /* PIOS_WDG_RADIORECEIVE */ + + return 0; +} + + +/** + * Initialise the module + * \return -1 if initialisation failed + * \return 0 on success + */ +static int32_t RadioInitialize(void) +{ + + // See if this module is enabled. +#ifndef RADIO_BUILTIN + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + HwSettingsOptionalModulesGet(optionalModules); + if (optionalModules[HWSETTINGS_OPTIONALMODULES_RADIO] != HWSETTINGS_OPTIONALMODULES_ENABLED) + return -1; +#endif + + // Initalize out UAVOs + PipXSettingsInitialize(); + PipXStatusInitialize(); + + PipXSettingsData pipxSettings; + PipXSettingsGet(&pipxSettings); + + /* Retrieve hardware settings. */ + pios_rfm22b_cfg.frequencyHz = pipxSettings.Frequency; + pios_rfm22b_cfg.RFXtalCap = pipxSettings.FrequencyCalibration; + switch (pipxSettings.RFSpeed) + { + case PIPXSETTINGS_RFSPEED_2400: + pios_rfm22b_cfg.maxRFBandwidth = 2000; + break; + case PIPXSETTINGS_RFSPEED_4800: + pios_rfm22b_cfg.maxRFBandwidth = 4000; + break; + case PIPXSETTINGS_RFSPEED_9600: + pios_rfm22b_cfg.maxRFBandwidth = 9600; + break; + case PIPXSETTINGS_RFSPEED_19200: + pios_rfm22b_cfg.maxRFBandwidth = 19200; + break; + case PIPXSETTINGS_RFSPEED_38400: + pios_rfm22b_cfg.maxRFBandwidth = 32000; + break; + case PIPXSETTINGS_RFSPEED_57600: + pios_rfm22b_cfg.maxRFBandwidth = 64000; + break; + case PIPXSETTINGS_RFSPEED_115200: + pios_rfm22b_cfg.maxRFBandwidth = 128000; + break; + } + switch (pipxSettings.MaxRFPower) + { + case PIPXSETTINGS_MAXRFPOWER_125: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0; + break; + case PIPXSETTINGS_MAXRFPOWER_16: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_1; + break; + case PIPXSETTINGS_MAXRFPOWER_316: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_2; + break; + case PIPXSETTINGS_MAXRFPOWER_63: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_3; + break; + case PIPXSETTINGS_MAXRFPOWER_126: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_4; + break; + case PIPXSETTINGS_MAXRFPOWER_25: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_5; + break; + case PIPXSETTINGS_MAXRFPOWER_50: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_6; + break; + case PIPXSETTINGS_MAXRFPOWER_100: + pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_7; + break; + } + + /* Initalize the RFM22B radio COM device. */ + { + if (PIOS_RFM22B_Init(&pios_rfm22b_id, &pios_rfm22b_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, + rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + + // Initialize the packet handler + PacketHandlerConfig pios_ph_cfg = { + .default_destination_id = 0xffffffff, // Broadcast + .source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id), + .win_size = PIOS_PH_WIN_SIZE, + .max_connections = PIOS_PH_MAX_CONNECTIONS, + }; + pios_packet_handler = PHInitialize(&pios_ph_cfg); + + // allocate and initialize the static data storage only if module is enabled + data = (RadioData *)pvPortMalloc(sizeof(RadioData)); + if (!data) + return -1; + + // Initialize the statistics. + data->radioTxErrors = 0; + data->radioRxErrors = 0; + data->packetErrors = 0; + data->droppedPackets = 0; + data->comTxRetries = 0; + data->UAVTalkErrors = 0; + data->RSSI = -127; + + // Initialize the detected device statistics. + for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) + { + data->pairStats[i].pairID = 0; + data->pairStats[i].rssi = -127; + data->pairStats[i].retries = 0; + data->pairStats[i].errors = 0; + data->pairStats[i].uavtalk_errors = 0; + data->pairStats[i].resets = 0; + data->pairStats[i].dropped = 0; + data->pairStats[i].lastContact = 0; + } + // The first slot is reserved for our current pairID + PipXSettingsPairIDGet(&(data->pairStats[0].pairID)); + data->destination_id = data->pairStats[0].pairID ? data->pairStats[0].pairID : 0xffffffff; + + // Create the packet queue. + data->radioPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); + + // Register the callbacks with the packet handler + PHRegisterStatusHandler(pios_packet_handler, StatusHandler); + PHRegisterOutputStream(pios_packet_handler, transmitPacket); + PHRegisterPPMHandler(pios_packet_handler, PPMHandler); + + return 0; +} +MODULE_INITCALL(RadioInitialize, RadioStart) + +/** + * The task that receives packets from the radio. + */ +static void radioReceiveTask(void *parameters) +{ + PHPacketHandle p = NULL; + + /* Handle radio -> usart/usb direction */ + while (1) { + uint32_t rx_bytes; + +#ifdef PIOS_WDG_RADIORECEIVE + // Update the watchdog timer. + PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); +#endif /* PIOS_INCLUDE_WDG */ + + // Get a RX packet from the packet handler if required. + if (p == NULL) + p = PHGetRXPacket(pios_packet_handler); + + if(p == NULL) { + // Wait a bit for a packet to come available. + vTaskDelay(5); + continue; + } + + // Receive data from the radio port + rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY); + if(rx_bytes == 0) + continue; + data->rxBytes += rx_bytes; + + // Verify that the packet is valid and pass it on. + bool rx_error = PHVerifyPacket(pios_packet_handler, p, rx_bytes) < 0; + if(rx_error) + data->packetErrors++; + PHReceivePacket(pios_packet_handler, p, rx_error); + p = NULL; + } +} + +/** + * Send packets to the radio. + */ +static void sendPacketTask(void *parameters) +{ + PHPacketHandle p; + + // Loop forever + while (1) { +#ifdef PIOS_INCLUDE_WDG + // Update the watchdog timer. + //PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET); +#endif /* PIOS_INCLUDE_WDG */ + // Wait for a packet on the queue. + if (xQueueReceive(data->radioPacketQueue, &p, MAX_PORT_DELAY) == pdTRUE) { + PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p)); + PHReleaseTXPacket(pios_packet_handler, p); + } + } +} + +/** + * Transmit a packet to the radio port. + * \param[in] buf Data buffer to send + * \param[in] length Length of buffer + * \return -1 on failure + * \return number of bytes transmitted on success + */ +static int32_t transmitPacket(PHPacketHandle p) +{ + uint16_t len = PH_PACKET_SIZE(p); + data->txBytes += len; + if (xQueueSend(data->radioPacketQueue, &p, portMAX_DELAY) != pdTRUE) + return -1; + return len; +} + +/** + * Receive a status packet + * \param[in] status The status structure + */ +static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) +{ + uint32_t id = status->header.source_id; + bool found = false; + // Have we seen this device recently? + uint8_t id_idx = 0; + for ( ; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) + if(data->pairStats[id_idx].pairID == id) + { + found = true; + break; + } + + // If we have seen it, update the RSSI and reset the last contact couter + if(found) + { + data->pairStats[id_idx].rssi = rssi; + data->pairStats[id_idx].retries = status->retries; + data->pairStats[id_idx].errors = status->errors; + data->pairStats[id_idx].uavtalk_errors = status->uavtalk_errors; + data->pairStats[id_idx].resets = status->resets; + data->pairStats[id_idx].dropped = status->dropped; + data->pairStats[id_idx].lastContact = 0; + } + + // If we haven't seen it, find a slot to put it in. + if (!found) + { + uint32_t pairID; + PipXSettingsPairIDGet(&pairID); + + uint8_t min_idx = 0; + if(id != pairID) + { + int8_t min_rssi = data->pairStats[0].rssi; + for (id_idx = 1; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) + { + if(data->pairStats[id_idx].rssi < min_rssi) + { + min_rssi = data->pairStats[id_idx].rssi; + min_idx = id_idx; + } + } + } + data->pairStats[min_idx].pairID = id; + data->pairStats[min_idx].rssi = rssi; + data->pairStats[min_idx].retries = status->retries; + data->pairStats[min_idx].errors = status->errors; + data->pairStats[min_idx].uavtalk_errors = status->uavtalk_errors; + data->pairStats[min_idx].resets = status->resets; + data->pairStats[min_idx].dropped = status->dropped; + data->pairStats[min_idx].lastContact = 0; + } +} + +/** + * The stats update task. + */ +static void radioStatusTask(void *parameters) +{ + PHStatusPacket status_packet; + + while (1) { + PipXStatusData pipxStatus; + uint32_t pairID; + + // Get object data + PipXStatusGet(&pipxStatus); + PipXSettingsPairIDGet(&pairID); + + // Update the status + pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + pipxStatus.Retries = data->comTxRetries; + pipxStatus.Errors = data->packetErrors; + pipxStatus.UAVTalkErrors = data->UAVTalkErrors; + pipxStatus.Dropped = data->droppedPackets; + pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id); + pipxStatus.TXRate = (uint16_t)((float)(data->txBytes * 1000) / STATS_UPDATE_PERIOD_MS); + data->txBytes = 0; + pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS); + data->rxBytes = 0; + pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED; + pipxStatus.RSSI = data->RSSI; + LINK_LED_OFF; + + // Update the potential pairing contacts + for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) + { + pipxStatus.PairIDs[i] = data->pairStats[i].pairID; + pipxStatus.PairSignalStrengths[i] = data->pairStats[i].rssi; + data->pairStats[i].lastContact++; + // Remove this device if it's stale. + if(data->pairStats[i].lastContact > MAX_LOST_CONTACT_TIME) + { + data->pairStats[i].pairID = 0; + data->pairStats[i].rssi = -127; + data->pairStats[i].retries = 0; + data->pairStats[i].errors = 0; + data->pairStats[i].uavtalk_errors = 0; + data->pairStats[i].resets = 0; + data->pairStats[i].dropped = 0; + data->pairStats[i].lastContact = 0; + } + // Add the paired devices statistics to ours. + if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127)) + { + pipxStatus.Retries += data->pairStats[i].retries; + pipxStatus.Errors += data->pairStats[i].errors; + pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors; + pipxStatus.Dropped += data->pairStats[i].dropped; + pipxStatus.Resets += data->pairStats[i].resets; + pipxStatus.Dropped += data->pairStats[i].dropped; + pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED; + LINK_LED_ON; + } + } + + // Update the object + PipXStatusSet(&pipxStatus); + + // Broadcast the status. + { + static uint16_t cntr = 0; + if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS) + { + // Queue the status message + status_packet.header.destination_id = 0xffffffff; + status_packet.header.type = PACKET_TYPE_STATUS; + status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet); + status_packet.header.source_id = pipxStatus.DeviceID; + status_packet.retries = data->comTxRetries; + status_packet.errors = data->packetErrors; + status_packet.uavtalk_errors = data->UAVTalkErrors; + status_packet.dropped = data->droppedPackets; + status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id); + PHPacketHandle sph = (PHPacketHandle)&status_packet; + PHTransmitPacket(PIOS_PACKET_HANDLER, sph); + cntr = 0; + } + } + + // Delay until the next update period. + vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); + } +} + +/** + * Receive a ppm packet + * \param[in] channels The ppm channels + */ +static void PPMHandler(uint16_t *channels) +{ + GCSReceiverData rcvr; + + // Copy the receiver channels into the GCSReceiver object. + for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) + rcvr.Channel[i] = channels[i]; + + // Set the GCSReceiverData object. + GCSReceiverSet(&rcvr); +} diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index eb674cbdd..572eacf4d 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -68,25 +68,13 @@ // **************** // Private types -typedef struct { - uint32_t pairID; - uint16_t retries; - uint16_t errors; - uint16_t uavtalk_errors; - uint16_t resets; - uint16_t dropped; - int8_t rssi; - uint8_t lastContact; -} PairStats; - typedef struct { uint32_t comPort; UAVTalkConnection UAVTalkCon; xQueueHandle sendQueue; xQueueHandle recvQueue; - xQueueHandle gcsQueue; uint16_t wdg; - bool checkHID; + bool isGCS; } UAVTalkComTaskParams; typedef struct { @@ -94,10 +82,7 @@ typedef struct { // The task handles. xTaskHandle GCSUAVTalkRecvTaskHandle; xTaskHandle UAVTalkRecvTaskHandle; - xTaskHandle radioReceiveTaskHandle; - xTaskHandle sendPacketTaskHandle; xTaskHandle UAVTalkSendTaskHandle; - xTaskHandle radioStatusTaskHandle; xTaskHandle transparentCommTaskHandle; xTaskHandle ppmInputTaskHandle; @@ -114,15 +99,8 @@ typedef struct { // Error statistics. uint32_t comTxErrors; uint32_t comTxRetries; - uint32_t comRxErrors; - uint32_t radioTxErrors; - uint32_t radioTxRetries; - uint32_t radioRxErrors; uint32_t UAVTalkErrors; - uint32_t packetErrors; uint32_t droppedPackets; - uint16_t txBytes; - uint16_t rxBytes; // The destination ID uint32_t destination_id; @@ -131,9 +109,6 @@ typedef struct { portTickType send_timeout; uint16_t min_packet_size; - // Track other radios that are in range. - PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM]; - // The RSSI of the last packet received. int8_t RSSI; @@ -155,19 +130,13 @@ typedef struct { // Private functions static void UAVTalkRecvTask(void *parameters); -static void radioReceiveTask(void *parameters); -static void sendPacketTask(void *parameters); static void UAVTalkSendTask(void *parameters); static void transparentCommTask(void * parameters); -static void radioStatusTask(void *parameters); static void ppmInputTask(void *parameters); static int32_t UAVTalkSendHandler(uint8_t * data, int32_t length); static int32_t GCSUAVTalkSendHandler(uint8_t * data, int32_t length); -static int32_t transmitPacket(PHPacketHandle packet); static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc); static void transmitData(uint32_t outputPort, uint8_t *buf, uint8_t len, bool checkHid); -static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc); -static void PPMHandler(uint16_t *channels); static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length); static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms); static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port); @@ -187,6 +156,11 @@ static RadioComBridgeData *data; static int32_t RadioComBridgeStart(void) { if(data) { + + // Register the callbacks with the packet handler + // This has to happen after the Radio module is initialized. + PHRegisterDataHandler(pios_packet_handler, receiveData); + // Start the primary tasks for receiving/sending UAVTalk packets from the GCS. xTaskCreate(UAVTalkRecvTask, (signed char *)"GCSUAVTalkRecvTask", STACK_SIZE_BYTES, (void*)&(data->gcs_uavtalk_params), TASK_PRIORITY + 2, &(data->GCSUAVTalkRecvTaskHandle)); xTaskCreate(UAVTalkSendTask, (signed char *)"GCSUAVTalkSendTask", STACK_SIZE_BYTES, (void*)&(data->gcs_uavtalk_params), TASK_PRIORITY+ 2, &(data->UAVTalkSendTaskHandle)); @@ -202,19 +176,15 @@ static int32_t RadioComBridgeStart(void) // Start the tasks if(PIOS_COM_TRANS_COM) xTaskCreate(transparentCommTask, (signed char *)"transparentComm", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->transparentCommTaskHandle)); - xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY+ 2, &(data->radioReceiveTaskHandle)); - xTaskCreate(sendPacketTask, (signed char *)"SendPacketTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->sendPacketTaskHandle)); - xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); if(PIOS_PPM_RECEIVER) xTaskCreate(ppmInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->ppmInputTaskHandle)); + #ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_COMGCS); if(PIOS_COM_UAVTALK) PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK); if(PIOS_COM_TRANS_COM) PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM); - PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE); - //PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET); if(PIOS_PPM_RECEIVER) PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT); #endif @@ -247,6 +217,8 @@ static int32_t RadioComBridgeInitialize(void) data->GCSUAVTalkCon = UAVTalkInitialize(&GCSUAVTalkSendHandler); if (PIOS_COM_UAVTALK) data->UAVTalkCon = UAVTalkInitialize(&UAVTalkSendHandler); + else + data->UAVTalkCon = 0; // Initialize the queues. data->ppmOutQueue = 0; @@ -261,62 +233,34 @@ static int32_t RadioComBridgeInitialize(void) } // Initialize the statistics. - data->radioTxErrors = 0; - data->radioTxRetries = 0; - data->radioRxErrors = 0; data->comTxErrors = 0; data->comTxRetries = 0; - data->comRxErrors = 0; data->UAVTalkErrors = 0; - data->packetErrors = 0; data->RSSI = -127; - // Register the callbacks with the packet handler - PHRegisterOutputStream(pios_packet_handler, transmitPacket); - PHRegisterDataHandler(pios_packet_handler, receiveData); - PHRegisterPPMHandler(pios_packet_handler, PPMHandler); - PHRegisterStatusHandler(pios_packet_handler, StatusHandler); - // Initialize the packet send timeout data->send_timeout = 25; // ms data->min_packet_size = 50; - // Initialize the detected device statistics. - for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) - { - data->pairStats[i].pairID = 0; - data->pairStats[i].rssi = -127; - data->pairStats[i].retries = 0; - data->pairStats[i].errors = 0; - data->pairStats[i].uavtalk_errors = 0; - data->pairStats[i].resets = 0; - data->pairStats[i].dropped = 0; - data->pairStats[i].lastContact = 0; - } - // The first slot is reserved for our current pairID - PipXSettingsPairIDGet(&(data->pairStats[0].pairID)); - // Configure our UAVObjects for updates. UAVObjConnectQueue(UAVObjGetByID(PIPXSTATUS_OBJID), data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ); UAVObjConnectQueue(UAVObjGetByID(GCSRECEIVER_OBJID), data->uavtalkEventQueue ? data->uavtalkEventQueue : data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ); UAVObjConnectQueue(UAVObjGetByID(OBJECTPERSISTENCE_OBJID), data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL); // Initialize the UAVTalk comm parameters. + data->gcs_uavtalk_params.isGCS = true; data->gcs_uavtalk_params.UAVTalkCon = data->GCSUAVTalkCon; - data->gcs_uavtalk_params.sendQueue = data->radioPacketQueue; + data->gcs_uavtalk_params.sendQueue = data->UAVTalkCon; data->gcs_uavtalk_params.recvQueue = data->gcsEventQueue; data->gcs_uavtalk_params.wdg = PIOS_WDG_COMGCS; - data->gcs_uavtalk_params.checkHID = true; data->gcs_uavtalk_params.comPort = PIOS_COM_GCS; if (PIOS_COM_UAVTALK) { - data->gcs_uavtalk_params.sendQueue = data->uavtalkEventQueue; + data->uavtalk_params.isGCS = false; data->uavtalk_params.UAVTalkCon = data->UAVTalkCon; - data->uavtalk_params.sendQueue = data->radioPacketQueue; + data->uavtalk_params.sendQueue = data->GCSUAVTalkCon; data->uavtalk_params.recvQueue = data->uavtalkEventQueue; - data->uavtalk_params.gcsQueue = data->gcsEventQueue; data->uavtalk_params.wdg = PIOS_WDG_COMUAVTALK; - data->uavtalk_params.checkHID = false; data->uavtalk_params.comPort = PIOS_COM_UAVTALK; } @@ -336,6 +280,8 @@ static void UAVTalkRecvTask(void *parameters) BufferedReadHandle f = BufferedReadInit(params->comPort, TEMP_BUFFER_SIZE); while (1) { + bool HID_available = false; + xQueueHandle sendQueue = 0; #ifdef PIOS_INCLUDE_WDG // Update the watchdog timer. @@ -343,13 +289,16 @@ static void UAVTalkRecvTask(void *parameters) PIOS_WDG_UpdateFlag(params->wdg); #endif /* PIOS_INCLUDE_WDG */ - // Receive from USB HID if available, otherwise UAVTalk com if it's available. #if defined(PIOS_INCLUDE_USB) - // Determine input port (USB takes priority over telemetry port) - if (params->checkHID && PIOS_USB_CheckAvailable(0)) + // Is USB plugged in? + if (PIOS_USB_CheckAvailable(0)) + HID_available = true; +#endif /* PIOS_INCLUDE_USB */ + + // Receive from USB HID if available, otherwise UAVTalk com if it's available. + if (params->isGCS && HID_available) BufferedReadSetCom(f, PIOS_COM_USB_HID); else -#endif /* PIOS_INCLUDE_USB */ { if (params->comPort) BufferedReadSetCom(f, params->comPort); @@ -360,9 +309,14 @@ static void UAVTalkRecvTask(void *parameters) } } + // Send packets to the UAVTalk port if this is a GCS connction and UAVTalk port is configured + // or to the GCS port if this is a UAVTalk connection and USB is plugged in. + if ((params->isGCS && data->UAVTalkCon) || (!params->isGCS && HID_available)) + sendQueue = params->sendQueue; + // Read the next byte uint8_t rx_byte; - if(!BufferedRead(f, &rx_byte, MAX_PORT_DELAY)) + if (!BufferedRead(f, &rx_byte, MAX_PORT_DELAY)) continue; // Get a TX packet from the packet handler if required. @@ -386,7 +340,6 @@ static void UAVTalkRecvTask(void *parameters) // Initialize the packet. p->header.destination_id = data->destination_id; - p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); p->header.type = PACKET_TYPE_DATA; p->data[0] = rx_byte; p->header.data_size = 1; @@ -403,13 +356,6 @@ static void UAVTalkRecvTask(void *parameters) if (state == UAVTALK_STATE_COMPLETE) { - xQueueHandle sendQueue = params->sendQueue; -#if defined(PIOS_INCLUDE_USB) - if (params->gcsQueue) - if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID) - sendQueue = params->gcsQueue; -#endif /* PIOS_INCLUDE_USB */ - // Is this a local UAVObject? // We only generate GcsReceiver ojects, we don't consume them. if ((iproc->obj != NULL) && (iproc->objId != GCSRECEIVER_OBJID)) @@ -486,7 +432,10 @@ static void UAVTalkRecvTask(void *parameters) else { // Otherwise, queue the packet for transmission. - queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + if (sendQueue) + queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + else + PHTransmitPacket(PIOS_PACKET_HANDLER, p); } } else @@ -515,17 +464,14 @@ static void UAVTalkRecvTask(void *parameters) else { // Queue the packet for transmission. - queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + if (sendQueue) + queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + else + PHTransmitPacket(PIOS_PACKET_HANDLER, p); } p = NULL; } else if(state == UAVTALK_STATE_ERROR) { - xQueueHandle sendQueue = params->sendQueue; -#if defined(PIOS_INCLUDE_USB) - if (params->gcsQueue) - if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID) - sendQueue = params->gcsQueue; -#endif /* PIOS_INCLUDE_USB */ data->UAVTalkErrors++; // Send a NACK if required. @@ -540,84 +486,16 @@ static void UAVTalkRecvTask(void *parameters) else { // Transmit the packet anyway... - queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + if (sendQueue) + queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + else + PHTransmitPacket(PIOS_PACKET_HANDLER, p); } p = NULL; } } } -/** - * The radio to com bridge task. - */ -static void radioReceiveTask(void *parameters) -{ - PHPacketHandle p = NULL; - - /* Handle radio -> usart/usb direction */ - while (1) { - uint32_t rx_bytes; - -#ifdef PIOS_INCLUDE_WDG - // Update the watchdog timer. - PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); -#endif /* PIOS_INCLUDE_WDG */ - - // Get a RX packet from the packet handler if required. - if (p == NULL) - p = PHGetRXPacket(pios_packet_handler); - - if(p == NULL) { - DEBUG_PRINTF(2, "RX Packet Unavailable.!\n\r"); - // Wait a bit for a packet to come available. - vTaskDelay(5); - continue; - } - - // Receive data from the radio port - rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY); - if(rx_bytes == 0) - continue; - data->rxBytes += rx_bytes; - - // Verify that the packet is valid and pass it on. - if(PHVerifyPacket(pios_packet_handler, p, rx_bytes) > 0) { - UAVObjEvent ev; - ev.obj = (UAVObjHandle)p; - ev.event = EV_PACKET_RECEIVED; - xQueueSend(data->gcsEventQueue, &ev, portMAX_DELAY); - } else - { - data->packetErrors++; - PHReceivePacket(pios_packet_handler, p, true); - } - p = NULL; - } -} - -/** - * Send packets to the radio. - */ -static void sendPacketTask(void *parameters) -{ - UAVObjEvent ev; - - // Loop forever - while (1) { -#ifdef PIOS_INCLUDE_WDG - // Update the watchdog timer. - //PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET); -#endif /* PIOS_INCLUDE_WDG */ - // Wait for a packet on the queue. - if (xQueueReceive(data->radioPacketQueue, &ev, MAX_PORT_DELAY) == pdTRUE) { - PHPacketHandle p = (PHPacketHandle)ev.obj; - // Send the packet. - if(!PHTransmitPacket(pios_packet_handler, p)) - PHReleaseRXPacket(pios_packet_handler, p); - } - } -} - /** * Send packets to the com port. */ @@ -681,7 +559,7 @@ static void UAVTalkSendTask(void *parameters) { // Transmit the packet. PHPacketHandle p = (PHPacketHandle)ev.obj; - transmitData(params->comPort, p->data, p->header.data_size, params->checkHID); + UAVTalkSendBuf(params->UAVTalkCon, p->data, p->header.data_size); PHReleaseTXPacket(pios_packet_handler, p); } } @@ -721,7 +599,6 @@ static void transparentCommTask(void * parameters) // Initialize the packet. p->header.destination_id = data->destination_id; - p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); //p->header.type = PACKET_TYPE_ACKED_DATA; p->header.type = PACKET_TYPE_DATA; p->header.data_size = 0; @@ -771,97 +648,6 @@ static void transparentCommTask(void * parameters) } } -/** - * The stats update task. - */ -static void radioStatusTask(void *parameters) -{ - PHStatusPacket status_packet; - - while (1) { - PipXStatusData pipxStatus; - uint32_t pairID; - - // Get object data - PipXStatusGet(&pipxStatus); - PipXSettingsPairIDGet(&pairID); - - // Update the status - pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - pipxStatus.Retries = data->comTxRetries; - pipxStatus.Errors = data->packetErrors; - pipxStatus.UAVTalkErrors = data->UAVTalkErrors; - pipxStatus.Dropped = data->droppedPackets; - pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id); - pipxStatus.TXRate = (uint16_t)((float)(data->txBytes * 1000) / STATS_UPDATE_PERIOD_MS); - data->txBytes = 0; - pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS); - data->rxBytes = 0; - pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED; - pipxStatus.RSSI = data->RSSI; - LINK_LED_OFF; - - // Update the potential pairing contacts - for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i) - { - pipxStatus.PairIDs[i] = data->pairStats[i].pairID; - pipxStatus.PairSignalStrengths[i] = data->pairStats[i].rssi; - data->pairStats[i].lastContact++; - // Remove this device if it's stale. - if(data->pairStats[i].lastContact > MAX_LOST_CONTACT_TIME) - { - data->pairStats[i].pairID = 0; - data->pairStats[i].rssi = -127; - data->pairStats[i].retries = 0; - data->pairStats[i].errors = 0; - data->pairStats[i].uavtalk_errors = 0; - data->pairStats[i].resets = 0; - data->pairStats[i].dropped = 0; - data->pairStats[i].lastContact = 0; - } - // Add the paired devices statistics to ours. - if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127)) - { - pipxStatus.Retries += data->pairStats[i].retries; - pipxStatus.Errors += data->pairStats[i].errors; - pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors; - pipxStatus.Dropped += data->pairStats[i].dropped; - pipxStatus.Resets += data->pairStats[i].resets; - pipxStatus.Dropped += data->pairStats[i].dropped; - pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED; - LINK_LED_ON; - } - } - - // Update the object - PipXStatusSet(&pipxStatus); - - // Broadcast the status. - { - static uint16_t cntr = 0; - if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS) - { - // Queue the status message - status_packet.header.destination_id = 0xffffffff; - status_packet.header.type = PACKET_TYPE_STATUS; - status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet); - status_packet.header.source_id = pipxStatus.DeviceID; - status_packet.retries = data->comTxRetries; - status_packet.errors = data->packetErrors; - status_packet.uavtalk_errors = data->UAVTalkErrors; - status_packet.dropped = data->droppedPackets; - status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id); - PHPacketHandle sph = (PHPacketHandle)&status_packet; - queueEvent(data->radioPacketQueue, (void*)sph, 0, EV_TRANSMIT_PACKET); - cntr = 0; - } - } - - // Delay until the next update period. - vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); - } -} - /** * The PPM input task. */ @@ -885,13 +671,21 @@ static void ppmInputTask(void *parameters) if (data->ppmOutQueue) { ppm_packet.header.destination_id = data->destination_id; - ppm_packet.header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id); ppm_packet.header.type = PACKET_TYPE_PPM; ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); queueEvent(data->ppmOutQueue, (void*)pph, 0, EV_TRANSMIT_PACKET); } else - PPMHandler(ppm_packet.channels); + { + GCSReceiverData rcvr; + + // Copy the receiver channels into the GCSReceiver object. + for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) + rcvr.Channel[i] = ppm_packet.channels[i]; + + // Set the GCSReceiverData object. + GCSReceiverSet(&rcvr); + } // Delay until the next update period. vTaskDelay(PIOS_PPM_PACKET_UPDATE_PERIOD_MS / portTICK_RATE_MS); @@ -910,7 +704,7 @@ static int32_t UAVTalkSend(UAVTalkComTaskParams *params, uint8_t *buf, int32_t l { uint32_t outputPort = params->comPort; #if defined(PIOS_INCLUDE_USB) - if (params->checkHID) + if (params->isGCS) { // Determine output port (USB takes priority over telemetry port) if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID) @@ -947,19 +741,6 @@ static int32_t GCSUAVTalkSendHandler(uint8_t *buf, int32_t length) return UAVTalkSend(&(data->gcs_uavtalk_params), buf, length); } -/** - * Transmit a packet to the radio port. - * \param[in] buf Data buffer to send - * \param[in] length Length of buffer - * \return -1 on failure - * \return number of bytes transmitted on success - */ -static int32_t transmitPacket(PHPacketHandle p) -{ - data->txBytes += PH_PACKET_SIZE(p); - return PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p)); -} - /** * Receive a packet * \param[in] buf The received data buffer @@ -993,85 +774,13 @@ static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc) data->RSSI = rssi; // Packet data should go to transparent com if it's configured, - // USB HID if it's connected, otherwise, UAVTalk com if it's configured. - uint32_t outputPort = PIOS_COM_TRANS_COM ? PIOS_COM_TRANS_COM : PIOS_COM_UAVTALK; - bool checkHid = (PIOS_COM_TRANS_COM == 0); - transmitData(outputPort, buf, len, checkHid); -} - -/** - * Receive a status packet - * \param[in] status The status structure - */ -static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) -{ - uint32_t id = status->header.source_id; - bool found = false; - // Have we seen this device recently? - uint8_t id_idx = 0; - for ( ; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) - if(data->pairStats[id_idx].pairID == id) - { - found = true; - break; - } - - // If we have seen it, update the RSSI and reset the last contact couter - if(found) - { - data->pairStats[id_idx].rssi = rssi; - data->pairStats[id_idx].retries = status->retries; - data->pairStats[id_idx].errors = status->errors; - data->pairStats[id_idx].uavtalk_errors = status->uavtalk_errors; - data->pairStats[id_idx].resets = status->resets; - data->pairStats[id_idx].dropped = status->dropped; - data->pairStats[id_idx].lastContact = 0; - } - - // If we haven't seen it, find a slot to put it in. - if (!found) - { - uint32_t pairID; - PipXSettingsPairIDGet(&pairID); - - uint8_t min_idx = 0; - if(id != pairID) - { - int8_t min_rssi = data->pairStats[0].rssi; - for (id_idx = 1; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx) - { - if(data->pairStats[id_idx].rssi < min_rssi) - { - min_rssi = data->pairStats[id_idx].rssi; - min_idx = id_idx; - } - } - } - data->pairStats[min_idx].pairID = id; - data->pairStats[min_idx].rssi = rssi; - data->pairStats[min_idx].retries = status->retries; - data->pairStats[min_idx].errors = status->errors; - data->pairStats[min_idx].uavtalk_errors = status->uavtalk_errors; - data->pairStats[min_idx].resets = status->resets; - data->pairStats[min_idx].dropped = status->dropped; - data->pairStats[min_idx].lastContact = 0; - } -} - -/** - * Receive a ppm packet - * \param[in] channels The ppm channels - */ -static void PPMHandler(uint16_t *channels) -{ - GCSReceiverData rcvr; - - // Copy the receiver channels into the GCSReceiver object. - for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) - rcvr.Channel[i] = channels[i]; - - // Set the GCSReceiverData object. - GCSReceiverSet(&rcvr); + // or just send it through the UAVTalk link. + if (PIOS_COM_TRANS_COM) + transmitData(PIOS_COM_TRANS_COM, buf, len, false); + else if (data->UAVTalkCon) + UAVTalkSendBuf(data->UAVTalkCon, buf, len); + else + UAVTalkSendBuf(data->GCSUAVTalkCon, buf, len); } static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length) diff --git a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h index 71426d594..d500c86ea 100755 --- a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h @@ -138,8 +138,6 @@ extern uint32_t pios_i2c_flexi_adapter_id; // See also pios_board.c //------------------------ #define PIOS_SPI_MAX_DEVS 1 -extern uint32_t pios_spi_port_id; -#define PIOS_SPI_PORT (pios_spi_port_id) //------------------------- // PIOS_USART @@ -270,30 +268,40 @@ extern uint32_t pios_ppm_rcvr_id; // RFM22 //------------------------- -extern uint32_t pios_rfm22b_id; +#if defined(PIOS_INCLUDE_RFM22B) +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 +extern uint32_t pios_com_rfm22b_id; +#define PIOS_COM_RADIO (pios_com_rfm22b_id) +extern uint32_t pios_spi_rfm22b_id; +#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id) #define RFM22_EXT_INT_USE -#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx +extern uint32_t pios_rfm22b_id; +#endif /* PIOS_INCLUDE_RFM22B */ -#if defined(RFM22_EXT_INT_USE) -#define PIOS_RFM22_EXTI_GPIO_PORT GPIOA -#define PIOS_RFM22_EXTI_GPIO_PIN GPIO_Pin_2 -#define PIOS_RFM22_EXTI_PORT_SOURCE GPIO_PortSourceGPIOA -#define PIOS_RFM22_EXTI_PIN_SOURCE GPIO_PinSource2 -#define PIOS_RFM22_EXTI_CLK RCC_APB2Periph_GPIOA -#define PIOS_RFM22_EXTI_LINE EXTI_Line2 -#define PIOS_RFM22_EXTI_IRQn EXTI2_IRQn -#define PIOS_RFM22_EXTI_PRIO PIOS_IRQ_PRIO_LOW -#endif +//------------------------- +// Packet Handler +//------------------------- +#if defined(PIOS_INCLUDE_PACKET_HANDLER) +extern uint32_t pios_packet_handler; +#define PIOS_PACKET_HANDLER (pios_packet_handler) +#define PIOS_PH_MAX_PACKET 255 +#define PIOS_PH_WIN_SIZE 3 +#define PIOS_PH_MAX_CONNECTIONS 1 +#define RS_ECC_NPARITY 4 +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ //------------------------- // Packet Handler //------------------------- +#if defined(PIOS_INCLUDE_PACKET_HANDLER) uint32_t pios_packet_handler; -#define PIOS_INCLUDE_PACKET_HANDLER +#define PIOS_PACKET_HANDLER (pios_packet_handler) #define PIOS_PH_MAX_PACKET 255 #define PIOS_PH_WIN_SIZE 3 #define PIOS_PH_MAX_CONNECTIONS 1 +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ //------------------------- // Reed-Solomon ECC diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 1f65748ee..17c385c3e 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -51,13 +51,8 @@ #if defined(PIOS_INCLUDE_RFM22B) -#include // memmove - -#include -#include - +#include #include - #include /* Local Defines */ @@ -135,6 +130,17 @@ #define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps +#ifndef RX_LED_ON +#define RX_LED_ON +#define RX_LED_OFF +#define TX_LED_ON +#define TX_LED_OFF +#define LINK_LED_ON +#define LINK_LED_OFF +#define USB_LED_ON +#define USB_LED_OFF +#endif + // ************************************ // Normal data streaming // GFSK modulation @@ -172,21 +178,20 @@ uint32_t random32 = 0x459ab8d8; /* Local function forwared declarations */ static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); static void rfm22_processInt(void); -static void PIOS_RFM22_EXT_Int(void); static void rfm22_setTxMode(uint8_t mode); // SPI read/write functions void rfm22_startBurstWrite(uint8_t addr); inline void rfm22_burstWrite(uint8_t data) { - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, data); } void rfm22_endBurstWrite(void); void rfm22_write(uint8_t addr, uint8_t data); void rfm22_startBurstRead(uint8_t addr); inline uint8_t rfm22_burstRead(void) { - return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); + return PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); } void rfm22_endBurstRead(void); uint8_t rfm22_read(uint8_t addr); @@ -208,35 +213,6 @@ const struct pios_com_driver pios_rfm22b_com_driver = { .bind_rx_cb = PIOS_RFM22B_RegisterRxCallback, }; -// External interrupt configuration -static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { - .vector = PIOS_RFM22_EXT_Int, - .line = PIOS_RFM22_EXTI_LINE, - .pin = { - .gpio = PIOS_RFM22_EXTI_GPIO_PORT, - .init = { - .GPIO_Pin = PIOS_RFM22_EXTI_GPIO_PIN, - .GPIO_Mode = GPIO_Mode_IN_FLOATING, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = PIOS_RFM22_EXTI_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_RFM22_EXTI_PRIO, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = PIOS_RFM22_EXTI_LINE, - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Falling, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - // xtal 10 ppm, 434MHz #define LOOKUP_SIZE 14 const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; @@ -337,17 +313,6 @@ volatile int32_t afc_correction_Hz; // afc correction reading (in Hz) volatile int16_t temperature_reg; // the temperature sensor reading -#if defined(RFM22_DEBUG) -volatile uint8_t prev_device_status; // just for debugging -volatile uint8_t prev_int_status1; // " " -volatile uint8_t prev_int_status2; // " " -volatile uint8_t prev_ezmac_status; // " " - -const char *debug_msg = ""; -const char *error_msg = ""; -static uint32_t debug_val = 0; -#endif - volatile uint8_t osc_load_cap; // xtal frequency calibration value volatile uint8_t rssi; // the current RSSI (register value) @@ -447,7 +412,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; - + *rfm22b_id = (uint32_t)rfm22b_dev; // Initialize the TX pre-buffer pointer. @@ -469,6 +434,14 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; rfm22b_dev->resets = 0; + // Initialize our SPI interface + if (PIOS_SPI_Init(&PIOS_RFM22_SPI_PORT, cfg->spi_cfg)) { + PIOS_Assert(0); + } + + // Initialize the external interrupt. + PIOS_EXTI_Init(cfg->exti_cfg); + // Initialize the radio device. int initval = rfm22_init_normal(rfm22b_dev->deviceID, cfg->minFrequencyHz, cfg->maxFrequencyHz, 50000); @@ -504,7 +477,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) rfm22_setFreqCalibration(cfg->RFXtalCap); rfm22_setNominalCarrierFrequency(cfg->frequencyHz); - rfm22_setDatarate(cfg->maxRFBandwidth, TRUE); + rfm22_setDatarate(cfg->maxRFBandwidth, true); rfm22_setTxPower(cfg->maxTxPower); DEBUG_PRINTF(2, "\n\r"); @@ -666,16 +639,6 @@ static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id) } } -static void rfm22_setDebug(const char* msg) -{ - debug_msg = msg; -} - -static void rfm22_setError(const char* msg) -{ - error_msg = msg; -} - // ************************************ // SPI read/write @@ -685,15 +648,15 @@ void rfm22_startBurstWrite(uint8_t addr) PIOS_DELAY_WaituS(1); // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); } void rfm22_endBurstWrite(void) { // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); } void rfm22_write(uint8_t addr, uint8_t data) @@ -702,13 +665,13 @@ void rfm22_write(uint8_t addr, uint8_t data) PIOS_DELAY_WaituS(1); // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, data); // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); } void rfm22_startBurstRead(uint8_t addr) @@ -717,15 +680,15 @@ void rfm22_startBurstRead(uint8_t addr) PIOS_DELAY_WaituS(1); // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); } void rfm22_endBurstRead(void) { // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); } uint8_t rfm22_read(uint8_t addr) @@ -736,13 +699,13 @@ uint8_t rfm22_read(uint8_t addr) PIOS_DELAY_WaituS(1); // chip select line LOW - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f); - rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); + rdata = PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); return rdata; } @@ -751,37 +714,10 @@ uint8_t rfm22_read(uint8_t addr) // external interrupt -static void PIOS_RFM22_EXT_Int(void) +void PIOS_RFM22_EXT_Int(void) { - rfm22_setDebug("Ext Int"); if (!exec_using_spi) rfm22_processInt(); - rfm22_setDebug("Ext Done"); -} - -void rfm22_disableExtInt(void) -{ -#if defined(RFM22_EXT_INT_USE) - rfm22_setDebug("Disable Int"); - // Configure the external interrupt - GPIO_EXTILineConfig(PIOS_RFM22_EXTI_PORT_SOURCE, PIOS_RFM22_EXTI_PIN_SOURCE); - EXTI_InitTypeDef EXTI_InitStructure = pios_exti_rfm22b_cfg.exti.init; - EXTI_InitStructure.EXTI_LineCmd = DISABLE; - EXTI_Init(&EXTI_InitStructure); - - EXTI_ClearFlag(PIOS_RFM22_EXTI_LINE); - rfm22_setDebug("Disable Int done"); -#endif -} - -void rfm22_enableExtInt(void) -{ -#if defined(RFM22_EXT_INT_USE) - rfm22_setDebug("Ensable Int"); - if (PIOS_EXTI_Init(&pios_exti_rfm22b_cfg)) - PIOS_Assert(0); - rfm22_setDebug("Ensable Int done"); -#endif } @@ -823,7 +759,7 @@ uint32_t rfm22_maxFrequency(void) void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) { - exec_using_spi = TRUE; + exec_using_spi = true; // ******* @@ -869,7 +805,7 @@ void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) // DEBUG_PRINTF(2, "rf setFreq frequency_step_size: %0.2f\n\r", frequency_step_size); #endif - exec_using_spi = FALSE; + exec_using_spi = false; } uint32_t rfm22_getNominalCarrierFrequency(void) @@ -914,7 +850,7 @@ uint32_t rfm22_freqHopSize(void) void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) { - exec_using_spi = TRUE; + exec_using_spi = true; lookup_index = 0; while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) @@ -1046,7 +982,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) // ******* - exec_using_spi = FALSE; + exec_using_spi = false; } uint32_t rfm22_getDatarate(void) @@ -1059,7 +995,7 @@ uint32_t rfm22_getDatarate(void) void rfm22_setSSBandwidth(uint32_t bandwidth_index) { - exec_using_spi = TRUE; + exec_using_spi = true; ss_lookup_index = bandwidth_index; @@ -1095,14 +1031,14 @@ void rfm22_setSSBandwidth(uint32_t bandwidth_index) // ******* - exec_using_spi = FALSE; + exec_using_spi = false; } // ************************************ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) { - exec_using_spi = TRUE; + exec_using_spi = true; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1151,7 +1087,7 @@ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) // enable the receiver rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon); - exec_using_spi = FALSE; + exec_using_spi = false; } // ************************************ @@ -1175,14 +1111,14 @@ uint16_t rfm22_addHeader() uint8_t rfm22_txStart() { - if((tx_pre_buffer_size == 0) || (exec_using_spi == TRUE)) + if((tx_pre_buffer_size == 0) || (exec_using_spi == true)) { // Clear the TX buffer. tx_data_rd = tx_data_wr = 0; return 0; } - exec_using_spi = TRUE; + exec_using_spi = true; // Disable interrrupts. PIOS_IRQ_Disable(); @@ -1255,18 +1191,17 @@ uint8_t rfm22_txStart() TX_LED_ON; - exec_using_spi = FALSE; + exec_using_spi = false; return 1; } static void rfm22_setTxMode(uint8_t mode) { - rfm22_setDebug("setTxMode"); if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE) return; // invalid mode - exec_using_spi = TRUE; + exec_using_spi = true; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1356,9 +1291,8 @@ static void rfm22_setTxMode(uint8_t mode) // ******************* - exec_using_spi = FALSE; + exec_using_spi = false; - rfm22_setDebug("setTxMode end"); } // ************************************ @@ -1368,12 +1302,10 @@ void rfm22_processRxInt(void) { register uint8_t int_stat1 = int_status1; register uint8_t int_stat2 = int_status2; - rfm22_setDebug("processRxInt"); // FIFO under/over flow error. Restart RX mode. if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - rfm22_setError("R_UNDER/OVERRUN"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } @@ -1383,7 +1315,6 @@ void rfm22_processRxInt(void) { rf_mode = RX_WAIT_SYNC_MODE; RX_LED_ON; - rfm22_setDebug("pream_det"); } // Sync word detected @@ -1391,7 +1322,6 @@ void rfm22_processRxInt(void) { rf_mode = RX_DATA_MODE; RX_LED_ON; - rfm22_setDebug("sync_det"); // read the 10-bit signed afc correction value // bits 9 to 2 @@ -1420,7 +1350,6 @@ void rfm22_processRxInt(void) // The received packet is going to be larger than the specified length if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) { - rfm22_setError("r_size_error1"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } @@ -1428,7 +1357,6 @@ void rfm22_processRxInt(void) // Another packet length error. if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid)) { - rfm22_setError("r_size_error2"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } @@ -1452,7 +1380,6 @@ void rfm22_processRxInt(void) if (int_stat1 & RFM22_is1_icrerror) { rfm22_int_timer = 0; // reset the timer - rfm22_setError("CRC_ERR"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } @@ -1477,14 +1404,11 @@ void rfm22_processRxInt(void) if (rx_buffer_wr != len) { // we have a packet length error .. discard the packet - rfm22_setError("r_pack_len_error"); - debug_val = len; rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } // we have a valid received packet - rfm22_setDebug("VALID_R_PACKET"); if (rx_buffer_wr > 0) { @@ -1507,12 +1431,10 @@ void rfm22_processRxInt(void) if(!rfm22_txStart()) { // Switch to RX mode - rfm22_setDebug(" Set RX"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); } } - rfm22_setDebug("processRxInt end"); } void rfm22_processTxInt(void) @@ -1525,7 +1447,6 @@ void rfm22_processTxInt(void) // FIFO under/over flow error. Back to RX mode. if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - rfm22_setError("T_UNDER/OVERRUN"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } @@ -1544,7 +1465,6 @@ void rfm22_processTxInt(void) if (rfm22_int_timer >= 100) { rfm22_int_time_outs++; - rfm22_setError("T_TIMEOUT"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode return; } @@ -1564,31 +1484,27 @@ void rfm22_processTxInt(void) // Packet has been sent if (int_stat1 & RFM22_is1_ipksent) { - rfm22_setDebug(" T_Sent"); // Send another packet if it's available. if(!rfm22_txStart()) { // Switch to RX mode - rfm22_setDebug(" Set RX"); rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); return; } } - rfm22_setDebug("ProcessTxInt done"); } static void rfm22_processInt(void) { - rfm22_setDebug("ProcessInt"); // this is called from the external interrupt handler if (!initialized || power_on_reset) // we haven't yet been initialized return; - exec_using_spi = TRUE; + exec_using_spi = true; // Reset the supervisor timer. rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; @@ -1619,9 +1535,8 @@ static void rfm22_processInt(void) // the RF module has gone and done a reset - we need to re-initialize the rf module if (int_status2 & RFM22_is2_ipor) { - initialized = FALSE; - power_on_reset = TRUE; - rfm22_setError("Reset"); + initialized = false; + power_on_reset = true; // Need to do something here! return; } @@ -1661,21 +1576,19 @@ static void rfm22_processInt(void) break; } - exec_using_spi = FALSE; - - rfm22_setDebug("ProcessInt done"); + exec_using_spi = false; } // ************************************ int8_t rfm22_getRSSI(void) { - exec_using_spi = TRUE; + exec_using_spi = true; rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm rssi_dBm = (int8_t)(rssi >> 1) - 122; // convert to dBm - exec_using_spi = FALSE; + exec_using_spi = false; return rssi_dBm; } @@ -1757,32 +1670,32 @@ int8_t rfm22_currentMode(void) return rf_mode; } -// return TRUE if we are transmitting +// return true if we are transmitting bool rfm22_transmitting(void) { return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE); } -// return TRUE if the channel is clear to transmit on +// return true if the channel is clear to transmit on bool rfm22_channelIsClear(void) { if (!initialized) // we haven't yet been initialized - return FALSE; + return false; if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE) // we are receiving something or we are transmitting or we are scanning the spectrum - return FALSE; + return false; - return TRUE; + return true; } -// return TRUE if the transmiter is ready for use +// return true if the transmiter is ready for use bool rfm22_txReady(void) { if (!initialized) // we haven't yet been initialized - return FALSE; + return false; return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE && @@ -1807,11 +1720,11 @@ void rfm22_setFreqCalibration(uint8_t value) tx_data_rd = tx_data_wr = 0; } - exec_using_spi = TRUE; + exec_using_spi = true; rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); - exec_using_spi = FALSE; + exec_using_spi = false; if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE) rfm22_setTxMode(prev_rf_mode); @@ -1842,40 +1755,38 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq { initialized = false; -#if defined(RFM22_EXT_INT_USE) - rfm22_disableExtInt(); -#endif - power_on_reset = false; // **************** - exec_using_spi = TRUE; + exec_using_spi = true; // **************** // setup the SPI port // chip select line HIGH - PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); // set SPI port SCLK frequency .. 4.5MHz - PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16); + PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_16); // set SPI port SCLK frequency .. 2.25MHz - // PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_32); + // PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_32); // set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding - // PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_256); + // PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_256); // **************** // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio - PIOS_DELAY_WaitmS(26); // wait 26ms + // wait 26ms + PIOS_DELAY_WaitmS(26); for (int i = 50; i > 0; i--) { - PIOS_DELAY_WaitmS(1); // wait 1ms + // wait 1ms + PIOS_DELAY_WaitmS(1); // read the status registers int_status1 = rfm22_read(RFM22_interrupt_status1); @@ -1897,7 +1808,7 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // **************** - exec_using_spi = FALSE; + exec_using_spi = false; // **************** @@ -2019,197 +1930,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq return 0; // OK } -// ************************************ - -int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ -#if defined(RFM22_DEBUG) - DEBUG_PRINTF(2, "\n\rRF init scan spectrum\n\r"); -#endif - - int res = rfm22_resetModule(RX_SCAN_SPECTRUM, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - // rfm22_setSSBandwidth(0); - rfm22_setSSBandwidth(1); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output - - rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, 0); - - rfm22_write(RFM22_preamble_detection_ctrl1, 31 << 3); // 31-nibbles rx preamble detection - - // avoid packet detection - rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_encrc); - rfm22_write(RFM22_header_control1, 0x0f); - rfm22_write(RFM22_header_control2, 0x77); - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); - rfm22_write(RFM22_sync_word1, SYNC_BYTE_3 ^ 0xff); - rfm22_write(RFM22_sync_word0, SYNC_BYTE_4 ^ 0xff); - - // all the bits to be checked - rfm22_write(RFM22_header_enable3, 0xff); - rfm22_write(RFM22_header_enable2, 0xff); - rfm22_write(RFM22_header_enable1, 0xff); - rfm22_write(RFM22_header_enable0, 0xff); - - // set frequency hopping channel step size (multiples of 10kHz) - // rfm22_write(RFM22_frequency_hopping_step_size, 0); - - // set our nominal carrier frequency - rfm22_setNominalCarrierFrequency(min_frequency_hz); - - // set minimum tx power - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | 0); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - // rfm22_write(RFM22_vco_current_trimming, 0x7f); - // rfm22_write(RFM22_vco_calibration_override, 0x40); - // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - // Enable RF module external interrupt - rfm22_enableExtInt(); - - rfm22_setRxMode(RX_SCAN_SPECTRUM, true); - - initialized = true; - - return 0; // OK -} - -// ************************************ - -int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ -#if defined(RFM22_DEBUG) - DEBUG_PRINTF(2, "\n\rRF init TX stream\n\r"); -#endif - - int res = rfm22_resetModule(TX_STREAM_MODE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - frequency_hop_step_size_reg = 0; - - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - // disable the internal Tx & Rx packet handlers (without CRC) - rfm22_write(RFM22_data_access_control, 0); - - rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble - rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection - - rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header - rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // - - // rfm22_write(RFM22_modem_test, 0x01); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); - // rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency - - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power - // rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power - - // rfm22_write(RFM22_vco_current_trimming, 0x7f); - // rfm22_write(RFM22_vco_calibration_override, 0x40); - // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63) - rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63) - - // Enable RF module external interrupt - rfm22_enableExtInt(); - - initialized = true; - - return 0; // OK -} - -// ************************************ - -int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz) -{ -#if defined(RFM22_DEBUG) - DEBUG_PRINTF(2, "\n\rRF init RX stream\n\r"); -#endif - - int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - - frequency_hop_step_size_reg = 0; - - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE); - - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); - - // disable the internal Tx & Rx packet handlers (without CRC) - rfm22_write(RFM22_data_access_control, 0); - - rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble - rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection - - rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header - rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length). - - rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word - rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); // - - // no header bits to be checked - rfm22_write(RFM22_header_enable3, 0x00); - rfm22_write(RFM22_header_enable2, 0x00); - rfm22_write(RFM22_header_enable1, 0x00); - rfm22_write(RFM22_header_enable0, 0x00); - - // rfm22_write(RFM22_modem_test, 0x01); - - rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); - // rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen); - - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz) - - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency - - // rfm22_write(RFM22_vco_current_trimming, 0x7f); - // rfm22_write(RFM22_vco_calibration_override, 0x40); - // rfm22_write(RFM22_chargepump_current_trimming_override, 0x80); - - // RX FIFO Almost Full Threshold (0 - 63) - rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); - - // Enable RF module external interrupt - rfm22_enableExtInt(); - - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - - initialized = true; - - return 0; // OK -} - // ************************************ // Initialise this hardware layer module and the rf module @@ -2225,7 +1945,7 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ frequency_hop_step_size_reg = freq_hop_step_size; // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, TRUE); + rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, true); // FIFO mode, GFSK modulation uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; @@ -2322,9 +2042,6 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ // RX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); - // Enable RF module external interrupt - rfm22_enableExtInt(); - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); initialized = true; diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index aa00a835e..df9b6aa9e 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -33,6 +33,8 @@ /* Global Types */ struct pios_rfm22b_cfg { + const struct pios_spi_cfg * spi_cfg; /* Pointer to SPI interface configuration */ + const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */ uint32_t frequencyHz; uint32_t minFrequencyHz; uint32_t maxFrequencyHz; diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 792915546..4535a472e 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -591,6 +591,8 @@ typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len); // ************************************ +void PIOS_RFM22_EXT_Int(void); + uint32_t rfm22_minFrequency(void); uint32_t rfm22_maxFrequency(void); diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 63f2e7907..e00278f36 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -66,7 +66,7 @@ FLASH_TOOL = OPENOCD # List of modules to include OPTMODULES = -MODULES = RadioComBridge +MODULES = Radio RadioComBridge # Paths OPSYSTEM = ./System diff --git a/flight/PipXtreme/System/inc/pios_config.h b/flight/PipXtreme/System/inc/pios_config.h index a94b2af89..254d92026 100755 --- a/flight/PipXtreme/System/inc/pios_config.h +++ b/flight/PipXtreme/System/inc/pios_config.h @@ -61,6 +61,8 @@ #define PIOS_INCLUDE_WDG #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_FLASH_EEPROM +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_PACKET_HANDLER /* Defaults for Logging */ #define LOG_FILENAME "PIOS.LOG" @@ -96,6 +98,9 @@ /* PIOS Initcall infrastructure */ #define PIOS_INCLUDE_INITCALL +/* Always include the radio module */ +#define RADIO_BUILTIN + #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/PipXtreme/System/pios_board.c b/flight/PipXtreme/System/pios_board.c index 3a2dd0544..84aa36d50 100644 --- a/flight/PipXtreme/System/pios_board.c +++ b/flight/PipXtreme/System/pios_board.c @@ -33,20 +33,17 @@ #include #include -#define PIOS_COM_SERIAL_RX_BUF_LEN 128 -#define PIOS_COM_SERIAL_TX_BUF_LEN 128 +#define PIOS_COM_SERIAL_RX_BUF_LEN 256 +#define PIOS_COM_SERIAL_TX_BUF_LEN 256 -#define PIOS_COM_FLEXI_RX_BUF_LEN 128 +#define PIOS_COM_FLEXI_RX_BUF_LEN 256 #define PIOS_COM_FLEXI_TX_BUF_LEN 128 -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 128 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 128 +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256 -#define PIOS_COM_VCP_USB_RX_BUF_LEN 128 -#define PIOS_COM_VCP_USB_TX_BUF_LEN 128 - -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 128 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 128 +#define PIOS_COM_VCP_USB_RX_BUF_LEN 256 +#define PIOS_COM_VCP_USB_TX_BUF_LEN 256 uint32_t pios_com_telem_usb_id = 0; uint32_t pios_com_telemetry_id; @@ -56,8 +53,6 @@ uint32_t pios_com_uavtalk_com_id = 0; uint32_t pios_com_gcs_com_id = 0; uint32_t pios_com_trans_com_id = 0; uint32_t pios_com_debug_id = 0; -uint32_t pios_com_rfm22b_id = 0; -uint32_t pios_rfm22b_id = 0; uint32_t pios_ppm_rcvr_id = 0; /** @@ -70,11 +65,6 @@ void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); - /* Set up the SPI interface to the serial flash */ - if (PIOS_SPI_Init(&pios_spi_port_id, &pios_spi_port_cfg)) { - PIOS_Assert(0); - } - /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); @@ -120,10 +110,6 @@ void PIOS_Board_Init(void) { PIOS_TIM_InitClock(&tim_4_cfg); #endif /* PIOS_INCLUDE_TIM */ -#if defined(PIOS_INCLUDE_PACKET_HANDLER) - pios_packet_handler = PHInitialize(&pios_ph_cfg); -#endif /* PIOS_INCLUDE_PACKET_HANDLER */ - #if defined(PIOS_INCLUDE_USB) /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); @@ -309,88 +295,6 @@ void PIOS_Board_Init(void) { break; } -#if defined(PIOS_INCLUDE_RFM22B) - struct pios_rfm22b_cfg pios_rfm22b_cfg = { - .frequencyHz = 434000000, - .minFrequencyHz = 434000000 - 2000000, - .maxFrequencyHz = 434000000 + 2000000, - .RFXtalCap = 0x7f, - .maxRFBandwidth = 128000, - .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW - }; - - /* Retrieve hardware settings. */ - pios_rfm22b_cfg.frequencyHz = pipxSettings.Frequency; - pios_rfm22b_cfg.RFXtalCap = pipxSettings.FrequencyCalibration; - switch (pipxSettings.RFSpeed) - { - case PIPXSETTINGS_RFSPEED_2400: - pios_rfm22b_cfg.maxRFBandwidth = 2000; - break; - case PIPXSETTINGS_RFSPEED_4800: - pios_rfm22b_cfg.maxRFBandwidth = 4000; - break; - case PIPXSETTINGS_RFSPEED_9600: - pios_rfm22b_cfg.maxRFBandwidth = 9600; - break; - case PIPXSETTINGS_RFSPEED_19200: - pios_rfm22b_cfg.maxRFBandwidth = 19200; - break; - case PIPXSETTINGS_RFSPEED_38400: - pios_rfm22b_cfg.maxRFBandwidth = 32000; - break; - case PIPXSETTINGS_RFSPEED_57600: - pios_rfm22b_cfg.maxRFBandwidth = 64000; - break; - case PIPXSETTINGS_RFSPEED_115200: - pios_rfm22b_cfg.maxRFBandwidth = 128000; - break; - } - switch (pipxSettings.RFSpeed) - { - case PIPXSETTINGS_MAXRFPOWER_125: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0; - break; - case PIPXSETTINGS_MAXRFPOWER_16: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_1; - break; - case PIPXSETTINGS_MAXRFPOWER_316: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_2; - break; - case PIPXSETTINGS_MAXRFPOWER_63: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_3; - break; - case PIPXSETTINGS_MAXRFPOWER_126: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_4; - break; - case PIPXSETTINGS_MAXRFPOWER_25: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_5; - break; - case PIPXSETTINGS_MAXRFPOWER_50: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_6; - break; - case PIPXSETTINGS_MAXRFPOWER_100: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_7; - break; - } - - /* Initalize the RFM22B radio COM device. */ - { - if (PIOS_RFM22B_Init(&pios_rfm22b_id, &pios_rfm22b_cfg)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_RFM22B */ - /* Remap AFIO pin */ GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index 7df2c8132..5550b8ffd 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -72,7 +72,7 @@ void PIOS_SPI_port_irq_handler(void); void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_port_irq_handler"))); void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_port_irq_handler"))); -static const struct pios_spi_cfg pios_spi_port_cfg = +static const struct pios_spi_cfg pios_spi_rfm22b_cfg = { .regs = SPI1, @@ -176,15 +176,62 @@ static const struct pios_spi_cfg pios_spi_port_cfg = }, }; -uint32_t pios_spi_port_id; +uint32_t pios_spi_rfm22b_id; void PIOS_SPI_port_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_port_id); + PIOS_SPI_IRQ_Handler(pios_spi_rfm22b_id); } #endif /* PIOS_INCLUDE_SPI */ +#if defined(PIOS_INCLUDE_RFM22B) + +#include + +static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { + .vector = PIOS_RFM22_EXT_Int, + .line = EXTI_Line2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line2, + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Falling, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +#include + +struct pios_rfm22b_cfg pios_rfm22b_cfg = { + .spi_cfg = &pios_spi_rfm22b_cfg, + .exti_cfg = &pios_exti_rfm22b_cfg, + .frequencyHz = 434000000, + .minFrequencyHz = 434000000 - 2000000, + .maxFrequencyHz = 434000000 + 2000000, + .RFXtalCap = 0x7f, + .maxRFBandwidth = 128000, + .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW +}; + +#endif /* PIOS_INCLUDE_RFM22B */ + #if defined(PIOS_INCLUDE_ADC) /* @@ -537,14 +584,3 @@ const struct pios_eeprom_cfg pios_eeprom_cfg = { #include #endif /* PIOS_INCLUDE_RFM22B */ - -#if defined(PIOS_INCLUDE_PACKET_HANDLER) -#include - -// Initialize the packet handler -PacketHandlerConfig pios_ph_cfg = { - .winSize = PIOS_PH_WIN_SIZE, - .maxConnections = PIOS_PH_MAX_CONNECTIONS, -}; - -#endif /* PIOS_INCLUDE_PACKET_HANDLER */ From 415b86879c2b9d8c8f22b7ba449e5c948f971cca Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sat, 25 Aug 2012 11:45:43 -0700 Subject: [PATCH 384/508] Added the RFM22B driver to the Revo to support an RFM22B radio on the external SPI port. --- flight/Modules/Telemetry/telemetry.c | 76 +++++--- flight/PiOS/Boards/STM32F4xx_Revolution.h | 33 ++++ flight/Revolution/Makefile | 9 + flight/Revolution/System/inc/pios_config.h | 2 + flight/Revolution/UAVObjects.inc | 2 + .../board_hw_defs/revolution/board_hw_defs.c | 175 ++++++++++++++++++ shared/uavobjectdefinition/hwsettings.xml | 2 +- 7 files changed, 275 insertions(+), 24 deletions(-) diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index 2b04e0545..a1cc19c34 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -35,6 +35,10 @@ #include "flighttelemetrystats.h" #include "gcstelemetrystats.h" #include "hwsettings.h" +#if defined(PIOS_PACKET_HANDLER) +#include "pipxstatus.h" +#include "packet_handler.h" +#endif // Private constants #define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE @@ -80,6 +84,10 @@ static void processObjEvent(UAVObjEvent * ev); static void updateTelemetryStats(); static void gcsTelemetryStatsUpdated(); static void updateSettings(); +static uint32_t getComPort(); +#ifdef PIOS_PACKET_HANDLER +static void receivePacketData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc); +#endif /** * Initialise the telemetry module @@ -93,6 +101,13 @@ int32_t TelemetryStart(void) // Listen to objects of interest GCSTelemetryStatsConnectQueue(priorityQueue); + + // Register to receive data from the radio packet handler. + // This must be after the radio module is initialized. +#ifdef PIOS_PACKET_HANDLER + if (PIOS_PACKET_HANDLER) + PHRegisterDataHandler(PIOS_PACKET_HANDLER, receivePacketData); +#endif // Start telemetry tasks xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle); @@ -247,6 +262,11 @@ static void processObjEvent(UAVObjEvent * ev) retries = 0; success = -1; if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL || ((ev->event == EV_UPDATED_PERIODIC) && (updateMode != UPDATEMODE_THROTTLED))) { +#ifdef PIOS_PACKET_HANDLER + // Don't send PipXStatus objects over the radio link. + if ((ev->obj == PipXStatusHandle()) && (getComPort() == 0) && PIOS_PACKET_HANDLER) + return; +#endif // Send update to GCS (with retries) while (retries < MAX_RETRIES && success == -1) { success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, UAVObjGetTelemetryAcked(&metadata), REQ_TIMEOUT_MS); // call blocks until ack is received or timeout @@ -322,19 +342,10 @@ static void telemetryTxPriTask(void *parameters) */ static void telemetryRxTask(void *parameters) { - uint32_t inputPort; // Task loop while (1) { -#if defined(PIOS_INCLUDE_USB) - // Determine input port (USB takes priority over telemetry port) - if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) { - inputPort = PIOS_COM_TELEM_USB; - } else -#endif /* PIOS_INCLUDE_USB */ - { - inputPort = telemetryPort; - } + uint32_t inputPort = getComPort(); if (inputPort) { // Block until data are available @@ -362,23 +373,17 @@ static void telemetryRxTask(void *parameters) */ static int32_t transmitData(uint8_t * data, int32_t length) { - uint32_t outputPort; - - // Determine input port (USB takes priority over telemetry port) -#if defined(PIOS_INCLUDE_USB) - if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) { - outputPort = PIOS_COM_TELEM_USB; - } else -#endif /* PIOS_INCLUDE_USB */ - { - outputPort = telemetryPort; - } + uint32_t outputPort = getComPort(); if (outputPort) { return PIOS_COM_SendBuffer(outputPort, data, length); - } else { - return -1; } +#ifdef PIOS_PACKET_HANDLER + if (PIOS_PACKET_HANDLER) + if (PHTransmitData(PIOS_PACKET_HANDLER, data, length)) + return 0; +#endif + return -1; } /** @@ -564,6 +569,31 @@ static void updateSettings() } } +/** + * Determine input/output com port (USB takes priority over telemetry port) + */ +static uint32_t getComPort() { +#if defined(PIOS_INCLUDE_USB) + if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) + return PIOS_COM_TELEM_USB; + else +#endif /* PIOS_INCLUDE_USB */ + return telemetryPort; +} + +#ifdef PIOS_PACKET_HANDLER +/** + * Receive a packet + * \param[in] buf The received data buffer + * \param[in] length Length of buffer + */ +static void receivePacketData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc) +{ + for (uint8_t i = 0; i < len; ++i) + UAVTalkProcessInputStream(uavTalkCon, buf[i]); +} +#endif + /** * @} * @} diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 370abd2e3..42163b995 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -32,6 +32,9 @@ #include +#define DEBUG_LEVEL 2 +#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_aux_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_aux_id, __VA_ARGS__); }} + //------------------------ // Timers and Channels Used //------------------------ @@ -133,6 +136,26 @@ extern uint32_t pios_com_vcp_id; #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_DEBUG PIOS_COM_AUX +#if defined(PIOS_INCLUDE_RFM22B) +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 +extern uint32_t pios_com_rfm22b_id; +#define PIOS_COM_RADIO (pios_com_rfm22b_id) +extern uint32_t pios_spi_rfm22b_id; +#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id) +#endif /* PIOS_INCLUDE_RFM22B */ + +//------------------------- +// Packet Handler +//------------------------- +#if defined(PIOS_INCLUDE_PACKET_HANDLER) +extern uint32_t pios_packet_handler; +#define PIOS_PACKET_HANDLER (pios_packet_handler) +#define PIOS_PH_MAX_PACKET 255 +#define PIOS_PH_WIN_SIZE 3 +#define PIOS_PH_MAX_CONNECTIONS 1 +#define RS_ECC_NPARITY 4 +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ //------------------------ // TELEMETRY @@ -263,6 +286,16 @@ extern uint32_t pios_com_vcp_id; #define PIOS_USB_ENABLED 1 /* Should remove all references to this */ #define PIOS_USB_HID_MAX_DEVS 1 + +//------------------------- +// RFM22 +//------------------------- +#if defined(PIOS_INCLUDE_RFM22B) +extern uint32_t pios_rfm22b_id; +#define RFM22_EXT_INT_USE + +#endif /* PIOS_INCLUDE_RFM22B */ + #endif /* STM3210E_INS_H_ */ /** * @} diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index 88d154ba5..73462f033 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -57,6 +57,7 @@ MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += CameraStab MODULES += OveroSync MODULES += Telemetry +MODULES += Radio PYMODULES = #FlightPlan @@ -72,6 +73,7 @@ PIOSINC = $(PIOS)/inc OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = ../Libraries/inc +RSCODEINC = $(FLIGHTLIB)/rscode PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -141,6 +143,11 @@ SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(FLIGHTLIB)/packet_handler.c +## The Reed-Solomon FEC library +SRC += $(FLIGHTLIB)/rscode/rs.c +SRC += $(FLIGHTLIB)/rscode/berlekamp.c +SRC += $(FLIGHTLIB)/rscode/galois.c ## PIOS Hardware (STM32F4xx) include $(PIOS)/STM32F4xx/library.mk @@ -162,6 +169,7 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c SRC += $(PIOSCOMMON)/pios_usb_util.c +SRC += $(PIOSCOMMON)/pios_rfm22b.c include ./UAVObjects.inc SRC += $(UAVOBJSRC) @@ -203,6 +211,7 @@ EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(RSCODEINC) EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index 4bb7be2a7..2886b6c09 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -73,6 +73,8 @@ #define PIOS_INCLUDE_COM_AUX #define PIOS_INCLUDE_COM_AUXSBUS #define PIOS_INCLUDE_COM_FLEXI +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_PACKET_HANDLER #define PIOS_INCLUDE_GPS #define PIOS_INCLUDE_GPS_NMEA_PARSER diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index 5b99daef4..6e1a513d8 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -91,6 +91,8 @@ UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive +UAVOBJSRCFILENAMES += pipxsettings +UAVOBJSRCFILENAMES += pipxstatus UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index b54dd119d..91ca87ed8 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -447,6 +447,181 @@ void PIOS_SPI_flash_irq_handler(void) } #endif /* PIOS_FLASH_ON_ACCEL */ +#if defined(PIOS_INCLUDE_RFM22B) +#include +/* SPI3 Interface + * - Used for RFM22B radio + */ +void PIOS_SPI_rfm22b_irq_handler(void); +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_rfm22b_irq_handler"))); +void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_rfm22b_irq_handler"))); +static const struct pios_spi_cfg pios_spi_rfm22b_cfg = { + .regs = SPI3, + .remap = GPIO_AF_SPI3, + .init = { + //.SPI_Mode = SPI_Mode_Slave, + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + //.SPI_NSS = SPI_NSS_Hard, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + //.SPI_CRCPolynomial = 7, + .SPI_CRCPolynomial = 0, + //.SPI_CPOL = SPI_CPOL_High, + .SPI_CPOL = SPI_CPOL_Low, + //.SPI_CPHA = SPI_CPHA_2Edge, + .SPI_CPHA = SPI_CPHA_1Edge, + //.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, + }, + .use_crc = false, + .dma = { + .irq = { + // Note this is the stream ID that triggers interrupts (in this case TX) + .flags = (DMA_IT_TCIF7), + //.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2), + .init = { + .NVIC_IRQChannel = DMA1_Stream7_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .channel = DMA1_Stream0, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_PeripheralToMemory, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + //.DMA_Mode = DMA_Mode_Circular, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + //TODO: Enable FIFO + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + .tx = { + .channel = DMA1_Stream7, + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), + .DMA_DIR = DMA_DIR_MemoryToPeripheral, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + //.DMA_Mode = DMA_Mode_Circular, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_Medium, + .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + }, + }, + }, + .sclk = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .miso = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .mosi = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, + .slave_count = 1, + .ssel = { { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + } }, +}; + +uint32_t pios_spi_rfm22b_id; +void PIOS_SPI_rfm22b_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_rfm22b_id); +} + +static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { + .vector = PIOS_RFM22_EXT_Int, + .line = EXTI_Line0, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line0, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Falling, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +struct pios_rfm22b_cfg pios_rfm22b_cfg = { + .spi_cfg = &pios_spi_rfm22b_cfg, + .exti_cfg = &pios_exti_rfm22b_cfg, + .frequencyHz = 434000000, + .minFrequencyHz = 434000000 - 2000000, + .maxFrequencyHz = 434000000 + 2000000, + .RFXtalCap = 0x7f, + .maxRFBandwidth = 128000, + .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW +}; + +#endif /* PIOS_INCLUDE_RFM22B */ + #endif /* PIOS_INCLUDE_SPI */ #if defined(PIOS_OVERO_SPI) diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 99d828452..862e8514a 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -18,7 +18,7 @@ - + From 2edc976168ec546e6108c5c5bab84213694a6ae4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 13:46:55 -0500 Subject: [PATCH 385/508] Fix the VBUS sense pin --- flight/board_hw_defs/revomini/board_hw_defs.c | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 6f2873b05..377d12284 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -364,7 +364,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = { }, }, }; - +#endif /* PIOS_INCLUDE_COM_TELEM */ #ifdef PIOS_INCLUDE_COM_FLEXI @@ -415,6 +415,8 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = { #endif /* PIOS_INCLUDE_COM_FLEXI */ +#ifdef PIOS_INCLUDE_DSM + #include "pios_dsm_priv.h" static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { .regs = USART3, @@ -1067,9 +1069,9 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { }, }, .vsense = { - .gpio = GPIOD, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_11, + .GPIO_Pin = GPIO_Pin_13, .GPIO_Speed = GPIO_Speed_25MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, From 31ebb7bbd83ddf7894d95317cd7f7014b85a0c8a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 13:51:52 -0500 Subject: [PATCH 386/508] Remove the old BMA180 and L3GD20 code and fix the irq lines for the sensors. --- flight/RevoMini/System/pios_board.c | 104 +++------------------------- 1 file changed, 10 insertions(+), 94 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 7d6aab68d..84ff25183 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -86,11 +86,11 @@ void PIOS_ADC_DMC_irq_handler(void) #include "pios_hmc5883.h" static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { .vector = PIOS_HMC5883_IRQHandler, - .line = EXTI_Line5, + .line = EXTI_Line7, .pin = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_5, + .GPIO_Pin = GPIO_Pin_7, .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, @@ -107,7 +107,7 @@ static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { }, .exti = { .init = { - .EXTI_Line = EXTI_Line5, // matches above GPIO pin + .EXTI_Line = EXTI_Line7, // matches above GPIO pin .EXTI_Mode = EXTI_Mode_Interrupt, .EXTI_Trigger = EXTI_Trigger_Rising, .EXTI_LineCmd = ENABLE, @@ -135,13 +135,14 @@ static const struct pios_ms5611_cfg pios_ms5611_cfg = { }; #endif /* PIOS_INCLUDE_MS5611 */ + /** - * Configuration for the BMA180 chip + * Configuration for the MPU6000 chip */ -#if defined(PIOS_INCLUDE_BMA180) -#include "pios_bma180.h" -static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = { - .vector = PIOS_BMA180_IRQHandler, +#if defined(PIOS_INCLUDE_MPU6000) +#include "pios_mpu6000.h" +static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { + .vector = PIOS_MPU6000_IRQHandler, .line = EXTI_Line4, .pin = { .gpio = GPIOC, @@ -156,48 +157,6 @@ static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = { .irq = { .init = { .NVIC_IRQChannel = EXTI4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line4, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; -static const struct pios_bma180_cfg pios_bma180_cfg = { - .exti_cfg = &pios_exti_bma180_cfg, - .bandwidth = BMA_BW_600HZ, - .range = BMA_RANGE_8G, -}; -#endif /* PIOS_INCLUDE_BMA180 */ - -/** - * Configuration for the MPU6000 chip - */ -#if defined(PIOS_INCLUDE_MPU6000) -#include "pios_mpu6000.h" -static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { - .vector = PIOS_MPU6000_IRQHandler, - .line = EXTI_Line8, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, @@ -205,7 +164,7 @@ static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { }, .exti = { .init = { - .EXTI_Line = EXTI_Line8, // matches above GPIO pin + .EXTI_Line = EXTI_Line4, // matches above GPIO pin .EXTI_Mode = EXTI_Mode_Interrupt, .EXTI_Trigger = EXTI_Trigger_Rising, .EXTI_LineCmd = ENABLE, @@ -228,49 +187,6 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { }; #endif /* PIOS_INCLUDE_MPU6000 */ -/** - * Configuration for L3GD20 chip - */ -#if defined(PIOS_INCLUDE_L3GD20) -#include "pios_l3gd20.h" -static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = { - .vector = PIOS_L3GD20_IRQHandler, - .line = EXTI_Line8, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line8, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_l3gd20_cfg pios_l3gd20_cfg = { - .exti_cfg = &pios_exti_l3gd20_cfg, - .range = PIOS_L3GD20_SCALE_500_DEG, -}; -#endif /* PIOS_INCLUDE_L3GD20 */ - - static const struct flashfs_cfg flashfs_m25p_cfg = { .table_magic = 0x85FB3D35, .obj_magic = 0x3015A371, From 0decce582b939cae9d210a65f7ae32f1aa29eb66 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 14:19:15 -0500 Subject: [PATCH 387/508] Got all the sensors reading --- flight/Modules/Sensors/sensors.c | 1 - flight/RevoMini/Makefile | 15 +++++++++------ flight/RevoMini/System/inc/pios_config.h | 6 ++---- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 22d22b250..855986cba 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -47,7 +47,6 @@ */ #include "pios.h" -#include "attitude.h" #include "homelocation.h" #include "magnetometer.h" #include "magbias.h" diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index 7df49d2a7..db1d1bd3e 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -49,12 +49,15 @@ endif FLASH_TOOL = OPENOCD # List of modules to include -MODULES = Sensors Attitude/revolution ManualControl Stabilization Actuator -MODULES += Battery -MODULES += Altitude/revolution GPS FirmwareIAP -MODULES += Airspeed/revolution -MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner -MODULES += CameraStab +MODULES = Sensors +#MODULES += Attitude/revolution +#MODULES += ManualControl Stabilization Actuator +#MODULES += Battery +MODULES += Altitude/revolution +MODULES += GPS FirmwareIAP +#MODULES += Airspeed/revolution +#MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +#MODULES += CameraStab MODULES += Telemetry PYMODULES = #FlightPlan diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 076fe1626..5ebfc06d9 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -39,7 +39,7 @@ #define PIOS_INCLUDE_BL_HELPER /* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_ADC +//#define PIOS_INCLUDE_ADC #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_I2C #define PIOS_INCLUDE_IRQ @@ -61,14 +61,12 @@ #define PIOS_INCLUDE_MPU6000 #define PIOS_MPU6000_ACCEL #define PIOS_INCLUDE_MS5611 -#define PIOS_INCLUDE_ETASV3 +//#define PIOS_INCLUDE_ETASV3 //#define PIOS_INCLUDE_HCSR04 #define FLASH_FREERTOS /* Com systems to include */ #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_COM_TELEM -#define PIOS_INCLUDE_COM_AUX -#define PIOS_INCLUDE_COM_AUXSBUS #define PIOS_INCLUDE_COM_FLEXI #define PIOS_INCLUDE_GPS From c3906cfe90c9055fcb9ab11776eb8aa5d13bbe09 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 14:22:06 -0500 Subject: [PATCH 388/508] Reenable the other main modules --- flight/RevoMini/Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index db1d1bd3e..e078fbb0b 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -50,8 +50,8 @@ FLASH_TOOL = OPENOCD # List of modules to include MODULES = Sensors -#MODULES += Attitude/revolution -#MODULES += ManualControl Stabilization Actuator +MODULES += Attitude/revolution +MODULES += ManualControl Stabilization Actuator #MODULES += Battery MODULES += Altitude/revolution MODULES += GPS FirmwareIAP From e602b73a6f2b5ddf80c37f5bf8087214ff4475da Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 24 Aug 2012 19:25:02 -0700 Subject: [PATCH 389/508] Split out the PipX radio interface from RadioComBridge module to a separate Radio module. Now the RadioComBridge module just routes messages between the com ports and handles sending/receiving the PipX UAVOs. Conflicts: flight/Modules/RadioComBridge/RadioComBridge.c flight/PipXtreme/System/pios_board.c Conflicts: flight/Modules/RadioComBridge/RadioComBridge.c --- .../Modules/RadioComBridge/RadioComBridge.c | 42 +++++++++++-------- 1 file changed, 25 insertions(+), 17 deletions(-) diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 572eacf4d..02bf75f3f 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -55,8 +55,8 @@ #define BRIDGE_BUF_LEN 512 #define MAX_RETRIES 2 #define RETRY_TIMEOUT_MS 20 -#define STATS_UPDATE_PERIOD_MS 500 -#define RADIOSTATS_UPDATE_PERIOD_MS 250 +#define STATS_UPDATE_PERIOD_MS 1000 +#define RADIOSTATS_UPDATE_PERIOD_MS 500 #define MAX_LOST_CONTACT_TIME 4 #define PACKET_QUEUE_SIZE 10 #define MAX_PORT_DELAY 200 @@ -664,27 +664,35 @@ static void ppmInputTask(void *parameters) #endif /* PIOS_INCLUDE_WDG */ // Read the receiver. + bool valid_input_detected = false; for (uint8_t i = 1; i <= PIOS_PPM_NUM_INPUTS; ++i) + { ppm_packet.channels[i - 1] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i); - - // Send the PPM packet - if (data->ppmOutQueue) - { - ppm_packet.header.destination_id = data->destination_id; - ppm_packet.header.type = PACKET_TYPE_PPM; - ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); - queueEvent(data->ppmOutQueue, (void*)pph, 0, EV_TRANSMIT_PACKET); + if(ppm_packet.channels[i - 1] != PIOS_RCVR_TIMEOUT) + valid_input_detected = true; } - else + + // Send the PPM packet if it's valid + if (valid_input_detected) { - GCSReceiverData rcvr; + if (data->ppmOutQueue) + { + ppm_packet.header.destination_id = data->destination_id; + ppm_packet.header.type = PACKET_TYPE_PPM; + ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); + queueEvent(data->ppmOutQueue, (void*)pph, 0, EV_TRANSMIT_PACKET); + } + else + { + GCSReceiverData rcvr; - // Copy the receiver channels into the GCSReceiver object. - for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) - rcvr.Channel[i] = ppm_packet.channels[i]; + // Copy the receiver channels into the GCSReceiver object. + for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i) + rcvr.Channel[i] = ppm_packet.channels[i]; - // Set the GCSReceiverData object. - GCSReceiverSet(&rcvr); + // Set the GCSReceiverData object. + GCSReceiverSet(&rcvr); + } } // Delay until the next update period. From c5fda8208b2699631d679010fe647ce2503de663 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 14:41:03 -0500 Subject: [PATCH 390/508] TOFIX: For now hardcode a reversed orientation of MPU6000 for RevoMini --- flight/Modules/Sensors/sensors.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 855986cba..d73d00887 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -302,12 +302,12 @@ static void SensorsTask(void *parameters) while(xQueueReceive(queue, (void *) &mpu6000_data, gyro_samples == 0 ? 10 : 0) != errQUEUE_EMPTY) { - gyro_accum[0] += mpu6000_data.gyro_x; - gyro_accum[1] += mpu6000_data.gyro_y; + gyro_accum[0] += -mpu6000_data.gyro_x; + gyro_accum[1] += -mpu6000_data.gyro_y; gyro_accum[2] += mpu6000_data.gyro_z; - accel_accum[0] += mpu6000_data.accel_x; - accel_accum[1] += mpu6000_data.accel_y; + accel_accum[0] += -mpu6000_data.accel_x; + accel_accum[1] += -mpu6000_data.accel_y; accel_accum[2] += mpu6000_data.accel_z; gyro_samples ++; From b3dc6177022544879ec0bae31c8af2585ad26c3c Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sat, 25 Aug 2012 12:52:06 -0700 Subject: [PATCH 391/508] Fixed PPM output from updated RadioComBridge module. --- .../Modules/RadioComBridge/RadioComBridge.c | 25 ++++++++----------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 02bf75f3f..8a92e27ee 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -91,10 +91,8 @@ typedef struct { UAVTalkConnection GCSUAVTalkCon; // Queue handles. - xQueueHandle radioPacketQueue; xQueueHandle gcsEventQueue; xQueueHandle uavtalkEventQueue; - xQueueHandle ppmOutQueue; // Error statistics. uint32_t comTxErrors; @@ -221,15 +219,12 @@ static int32_t RadioComBridgeInitialize(void) data->UAVTalkCon = 0; // Initialize the queues. - data->ppmOutQueue = 0; - data->radioPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent)); data->gcsEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent)); if (PIOS_COM_UAVTALK) data->uavtalkEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent)); else { data->uavtalkEventQueue = 0; - data->ppmOutQueue = data->radioPacketQueue; } // Initialize the statistics. @@ -637,7 +632,7 @@ static void transparentCommTask(void * parameters) if (send_packet) { // Queue the packet for transmission. - queueEvent(data->radioPacketQueue, (void*)p, 0, EV_TRANSMIT_PACKET); + PHTransmitPacket(PIOS_PACKET_HANDLER, p); // Reset the timeout timeout = MAX_PORT_DELAY; @@ -675,14 +670,8 @@ static void ppmInputTask(void *parameters) // Send the PPM packet if it's valid if (valid_input_detected) { - if (data->ppmOutQueue) - { - ppm_packet.header.destination_id = data->destination_id; - ppm_packet.header.type = PACKET_TYPE_PPM; - ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); - queueEvent(data->ppmOutQueue, (void*)pph, 0, EV_TRANSMIT_PACKET); - } - else + // Set the GCSReceiver UAVO if we're connected to the FC. + if (data->UAVTalkCon) { GCSReceiverData rcvr; @@ -693,6 +682,14 @@ static void ppmInputTask(void *parameters) // Set the GCSReceiverData object. GCSReceiverSet(&rcvr); } + else + { + // Otherwise, send a PPM packet over the radio link. + ppm_packet.header.destination_id = data->destination_id; + ppm_packet.header.type = PACKET_TYPE_PPM; + ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet); + PHTransmitPacket(PIOS_PACKET_HANDLER, pph); + } } // Delay until the next update period. From daad1d6f8f4b2ce83cb33e2b635401d190bebc48 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:12:37 -0500 Subject: [PATCH 392/508] Sensors: Scope some variables to suppress warnings --- flight/Modules/Sensors/sensors.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index d73d00887..b9c3159de 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -225,8 +225,6 @@ static void SensorsTask(void *parameters) AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); } - int32_t read_good; - int32_t count; for (int i = 0; i < 3; i++) { accel_accum[i] = 0; @@ -244,6 +242,9 @@ static void SensorsTask(void *parameters) { struct pios_bma180_data accel; + int32_t read_good; + int32_t count; + count = 0; while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error) error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error; From 76bdb190d88e7fcc4ae95c2b114f9f75f18ad756 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:27:17 -0500 Subject: [PATCH 393/508] Link in the rfm module to the target --- flight/PiOS/Boards/STM32F4xx_RevoMini.h | 24 ++++++++- flight/PiOS/Boards/STM32F4xx_Revolution.h | 1 - flight/RevoMini/Makefile | 20 ++++++-- flight/RevoMini/System/inc/pios_config.h | 5 ++ flight/RevoMini/System/pios_board.c | 2 - flight/RevoMini/UAVObjects.inc | 2 + flight/board_hw_defs/revomini/board_hw_defs.c | 51 ++++++++++++++++++- 7 files changed, 94 insertions(+), 11 deletions(-) diff --git a/flight/PiOS/Boards/STM32F4xx_RevoMini.h b/flight/PiOS/Boards/STM32F4xx_RevoMini.h index 5a49f1fbb..36f5f1d0d 100644 --- a/flight/PiOS/Boards/STM32F4xx_RevoMini.h +++ b/flight/PiOS/Boards/STM32F4xx_RevoMini.h @@ -28,10 +28,12 @@ #ifndef STM3210E_INS_H_ -#define STM3210E_INS_H_ #include +#define DEBUG_LEVEL 0 +#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_aux_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_aux_id, __VA_ARGS__); }} + //------------------------ // Timers and Channels Used //------------------------ @@ -133,6 +135,26 @@ extern uint32_t pios_com_vcp_id; #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_DEBUG PIOS_COM_AUX +#if defined(PIOS_INCLUDE_RFM22B) +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 +extern uint32_t pios_com_rfm22b_id; +#define PIOS_COM_RADIO (pios_com_rfm22b_id) +extern uint32_t pios_spi_telem_flash_id; +#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id) +#endif /* PIOS_INCLUDE_RFM22B */ + +//------------------------- +// Packet Handler +//------------------------- +#if defined(PIOS_INCLUDE_PACKET_HANDLER) +extern uint32_t pios_packet_handler; +#define PIOS_PACKET_HANDLER (pios_packet_handler) +#define PIOS_PH_MAX_PACKET 255 +#define PIOS_PH_WIN_SIZE 3 +#define PIOS_PH_MAX_CONNECTIONS 1 +#define RS_ECC_NPARITY 4 +#endif /* PIOS_INCLUDE_PACKET_HANDLER */ //------------------------ // TELEMETRY diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 42163b995..585bfd2ad 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -28,7 +28,6 @@ #ifndef STM3210E_INS_H_ -#define STM3210E_INS_H_ #include diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index e078fbb0b..06dd2228f 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -1,10 +1,10 @@ ##### -# Project: OpenPilot INS +# Project: OpenPilot RevoMini # # -# Makefile for OpenPilot INS project +# Makefile for OpenPilot RevoMini project # -# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. +# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. # # # This program is free software; you can redistribute it and/or modify @@ -58,6 +58,7 @@ MODULES += GPS FirmwareIAP #MODULES += Airspeed/revolution #MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner #MODULES += CameraStab +MODULES += Radio MODULES += Telemetry PYMODULES = #FlightPlan @@ -74,6 +75,8 @@ PIOSINC = $(PIOS)/inc OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = ../Libraries/inc +RSCODE = $(FLIGHTLIB)/rscode +RSCODEINC = $(FLIGHTLIB)/rscode PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -85,8 +88,6 @@ STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc OPUAVOBJ = ../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -BOOT = ../Bootloaders/INS -BOOTINC = $(BOOT)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot @@ -144,6 +145,13 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c +## For RFM22b +SRC += $(FLIGHTLIB)/packet_handler.c +SRC += $(RSCODE)/berlekamp.c +SRC += $(RSCODE)/crcgen.c +SRC += $(RSCODE)/galois.c +SRC += $(RSCODE)/rs.c + ## PIOS Hardware (STM32F4xx) include $(PIOS)/STM32F4xx/library.mk @@ -157,6 +165,7 @@ SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_rfm22b.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_flash_jedec.c SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c @@ -205,6 +214,7 @@ EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(RSCODEINC) EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 5ebfc06d9..eb282fdd8 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -56,6 +56,11 @@ #define PIOS_INCLUDE_RTC #define PIOS_INCLUDE_WDG +/* Variables related to the RFM22B functionality */ +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_PACKET_HANDLER +#define RFM22_EXT_INT_USE + /* Select the sensors to include */ #define PIOS_INCLUDE_HMC5883 #define PIOS_INCLUDE_MPU6000 diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 84ff25183..d46f25610 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -292,8 +292,6 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm void PIOS_Board_Init(void) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - /* Delay system */ PIOS_DELAY_Init(); diff --git a/flight/RevoMini/UAVObjects.inc b/flight/RevoMini/UAVObjects.inc index 5b99daef4..552449996 100644 --- a/flight/RevoMini/UAVObjects.inc +++ b/flight/RevoMini/UAVObjects.inc @@ -68,6 +68,8 @@ UAVOBJSRCFILENAMES += overosyncstats UAVOBJSRCFILENAMES += overosyncsettings UAVOBJSRCFILENAMES += pathplannersettings UAVOBJSRCFILENAMES += pathdesired +UAVOBJSRCFILENAMES += pipxstatus +UAVOBJSRCFILENAMES += pipxsettings UAVOBJSRCFILENAMES += positionactual UAVOBJSRCFILENAMES += ratedesired UAVOBJSRCFILENAMES += revocalibration diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 377d12284..d5e3ff58a 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -314,6 +314,54 @@ void PIOS_SPI_telem_flash_irq_handler(void) PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id); } + +#if defined(PIOS_INCLUDE_RFM22B) +#include + +static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { + .vector = PIOS_RFM22_EXT_Int, + .line = EXTI_Line0, + .pin = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI0_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line0, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Falling, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +struct pios_rfm22b_cfg pios_rfm22b_cfg = { + .spi_cfg = &pios_spi_telem_flash_cfg, + .exti_cfg = &pios_exti_rfm22b_cfg, + .frequencyHz = 434000000, + .minFrequencyHz = 434000000 - 2000000, + .maxFrequencyHz = 434000000 + 2000000, + .RFXtalCap = 0x7f, + .maxRFBandwidth = 128000, + .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW +}; + +#endif /* PIOS_INCLUDE_RFM22B */ + #endif /* PIOS_INCLUDE_SPI */ #include @@ -331,8 +379,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = { .USART_WordLength = USART_WordLength_8b, .USART_Parity = USART_Parity_No, .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { From 81ddbda972b2ed8915dcc726fa0ba871016c01ea Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:12:37 -0500 Subject: [PATCH 394/508] Sensors: Scope some variables to suppress warnings --- flight/Modules/Sensors/sensors.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 22d22b250..01cdee594 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -226,8 +226,6 @@ static void SensorsTask(void *parameters) AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); } - int32_t read_good; - int32_t count; for (int i = 0; i < 3; i++) { accel_accum[i] = 0; @@ -245,6 +243,9 @@ static void SensorsTask(void *parameters) { struct pios_bma180_data accel; + int32_t read_good; + int32_t count; + count = 0; while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error) error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error; From b95a78cde5fde49b6da61ef65f0813747bcfa3d1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:32:01 -0500 Subject: [PATCH 395/508] Roll back changes on the revo target --- flight/PiOS/Boards/STM32F4xx_Revolution.h | 34 +--- flight/Revolution/Makefile | 9 - flight/Revolution/System/inc/pios_config.h | 2 - flight/Revolution/UAVObjects.inc | 2 - .../board_hw_defs/revolution/board_hw_defs.c | 175 ------------------ 5 files changed, 1 insertion(+), 221 deletions(-) diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 585bfd2ad..370abd2e3 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -28,12 +28,10 @@ #ifndef STM3210E_INS_H_ +#define STM3210E_INS_H_ #include -#define DEBUG_LEVEL 2 -#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_aux_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_aux_id, __VA_ARGS__); }} - //------------------------ // Timers and Channels Used //------------------------ @@ -135,26 +133,6 @@ extern uint32_t pios_com_vcp_id; #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_DEBUG PIOS_COM_AUX -#if defined(PIOS_INCLUDE_RFM22B) -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 -extern uint32_t pios_com_rfm22b_id; -#define PIOS_COM_RADIO (pios_com_rfm22b_id) -extern uint32_t pios_spi_rfm22b_id; -#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id) -#endif /* PIOS_INCLUDE_RFM22B */ - -//------------------------- -// Packet Handler -//------------------------- -#if defined(PIOS_INCLUDE_PACKET_HANDLER) -extern uint32_t pios_packet_handler; -#define PIOS_PACKET_HANDLER (pios_packet_handler) -#define PIOS_PH_MAX_PACKET 255 -#define PIOS_PH_WIN_SIZE 3 -#define PIOS_PH_MAX_CONNECTIONS 1 -#define RS_ECC_NPARITY 4 -#endif /* PIOS_INCLUDE_PACKET_HANDLER */ //------------------------ // TELEMETRY @@ -285,16 +263,6 @@ extern uint32_t pios_packet_handler; #define PIOS_USB_ENABLED 1 /* Should remove all references to this */ #define PIOS_USB_HID_MAX_DEVS 1 - -//------------------------- -// RFM22 -//------------------------- -#if defined(PIOS_INCLUDE_RFM22B) -extern uint32_t pios_rfm22b_id; -#define RFM22_EXT_INT_USE - -#endif /* PIOS_INCLUDE_RFM22B */ - #endif /* STM3210E_INS_H_ */ /** * @} diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index 73462f033..88d154ba5 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -57,7 +57,6 @@ MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += CameraStab MODULES += OveroSync MODULES += Telemetry -MODULES += Radio PYMODULES = #FlightPlan @@ -73,7 +72,6 @@ PIOSINC = $(PIOS)/inc OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = ../Libraries/inc -RSCODEINC = $(FLIGHTLIB)/rscode PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -143,11 +141,6 @@ SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c -SRC += $(FLIGHTLIB)/packet_handler.c -## The Reed-Solomon FEC library -SRC += $(FLIGHTLIB)/rscode/rs.c -SRC += $(FLIGHTLIB)/rscode/berlekamp.c -SRC += $(FLIGHTLIB)/rscode/galois.c ## PIOS Hardware (STM32F4xx) include $(PIOS)/STM32F4xx/library.mk @@ -169,7 +162,6 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c SRC += $(PIOSCOMMON)/pios_usb_util.c -SRC += $(PIOSCOMMON)/pios_rfm22b.c include ./UAVObjects.inc SRC += $(UAVOBJSRC) @@ -211,7 +203,6 @@ EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(RSCODEINC) EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/Revolution/System/inc/pios_config.h index 2886b6c09..4bb7be2a7 100644 --- a/flight/Revolution/System/inc/pios_config.h +++ b/flight/Revolution/System/inc/pios_config.h @@ -73,8 +73,6 @@ #define PIOS_INCLUDE_COM_AUX #define PIOS_INCLUDE_COM_AUXSBUS #define PIOS_INCLUDE_COM_FLEXI -#define PIOS_INCLUDE_RFM22B -#define PIOS_INCLUDE_PACKET_HANDLER #define PIOS_INCLUDE_GPS #define PIOS_INCLUDE_GPS_NMEA_PARSER diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index 6e1a513d8..5b99daef4 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -91,8 +91,6 @@ UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += pipxsettings -UAVOBJSRCFILENAMES += pipxstatus UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index a793b90f6..2bc703cd8 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -447,181 +447,6 @@ void PIOS_SPI_flash_irq_handler(void) } #endif /* PIOS_FLASH_ON_ACCEL */ -#if defined(PIOS_INCLUDE_RFM22B) -#include -/* SPI3 Interface - * - Used for RFM22B radio - */ -void PIOS_SPI_rfm22b_irq_handler(void); -void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_rfm22b_irq_handler"))); -void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_rfm22b_irq_handler"))); -static const struct pios_spi_cfg pios_spi_rfm22b_cfg = { - .regs = SPI3, - .remap = GPIO_AF_SPI3, - .init = { - //.SPI_Mode = SPI_Mode_Slave, - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - //.SPI_NSS = SPI_NSS_Hard, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - //.SPI_CRCPolynomial = 7, - .SPI_CRCPolynomial = 0, - //.SPI_CPOL = SPI_CPOL_High, - .SPI_CPOL = SPI_CPOL_Low, - //.SPI_CPHA = SPI_CPHA_2Edge, - .SPI_CPHA = SPI_CPHA_1Edge, - //.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case TX) - .flags = (DMA_IT_TCIF7), - //.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2), - .init = { - .NVIC_IRQChannel = DMA1_Stream7_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .channel = DMA1_Stream0, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - //.DMA_Mode = DMA_Mode_Circular, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream7, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - //.DMA_Mode = DMA_Mode_Circular, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - } }, -}; - -uint32_t pios_spi_rfm22b_id; -void PIOS_SPI_rfm22b_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_rfm22b_id); -} - -static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { - .vector = PIOS_RFM22_EXT_Int, - .line = EXTI_Line0, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line0, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Falling, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -struct pios_rfm22b_cfg pios_rfm22b_cfg = { - .spi_cfg = &pios_spi_rfm22b_cfg, - .exti_cfg = &pios_exti_rfm22b_cfg, - .frequencyHz = 434000000, - .minFrequencyHz = 434000000 - 2000000, - .maxFrequencyHz = 434000000 + 2000000, - .RFXtalCap = 0x7f, - .maxRFBandwidth = 128000, - .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW -}; - -#endif /* PIOS_INCLUDE_RFM22B */ - #endif /* PIOS_INCLUDE_SPI */ #if defined(PIOS_OVERO_SPI) From ad7a9b9cc327ea88295450ec241d12fc564278b1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:49:15 -0500 Subject: [PATCH 396/508] Switch the order of the SET_RC pins for flash and rfm22b --- flight/RevoMini/System/pios_board.c | 4 +++- flight/board_hw_defs/revomini/board_hw_defs.c | 23 ++++++++++--------- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index d46f25610..1fc2eaa8a 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -307,9 +307,11 @@ void PIOS_Board_Init(void) { PIOS_DEBUG_Assert(0); } +#if defined(PIOS_INCLUDE_FLASH) /* Connect flash to the approrpiate interface and configure it */ - PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 0, &flash_m25p_cfg); + PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 1, &flash_m25p_cfg); PIOS_FLASHFS_Init(&flashfs_m25p_cfg); +#endif /* Initialize UAVObject libraries */ EventDispatcherInitialize(); diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index d5e3ff58a..66532e0cc 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -285,16 +285,8 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { .GPIO_PuPd = GPIO_PuPd_NOPULL }, }, - .slave_count = 1, - .ssel = { { // Flash - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, + .slave_count = 2, + .ssel = { { // RFM22b .gpio = GPIOA, .init = { @@ -303,7 +295,16 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP - } }, + } }, + { // Flash + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + } }, }, }; From 9e25e887c2ffbe33dc246f1e75d3103bbdad1082 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 18:43:13 -0500 Subject: [PATCH 397/508] Temporarily disable flash chip and configure SPI for modem. --- flight/RevoMini/System/pios_board.c | 4 ++-- flight/board_hw_defs/revomini/board_hw_defs.c | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 1fc2eaa8a..e5f870e2f 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -309,8 +309,8 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_FLASH) /* Connect flash to the approrpiate interface and configure it */ - PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 1, &flash_m25p_cfg); - PIOS_FLASHFS_Init(&flashfs_m25p_cfg); + //PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 1, &flash_m25p_cfg); + //PIOS_FLASHFS_Init(&flashfs_m25p_cfg); #endif /* Initialize UAVObject libraries */ diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 66532e0cc..0a33a6ebb 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -200,9 +200,9 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { .SPI_NSS = SPI_NSS_Soft, .SPI_FirstBit = SPI_FirstBit_MSB, .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + .SPI_CPOL = SPI_CPOL_Low, + .SPI_CPHA = SPI_CPHA_1Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, }, .use_crc = false, .dma = { From a7b5fcd77c3f6bcfae9a10b335f771e3ca4277d0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 18:48:30 -0500 Subject: [PATCH 398/508] Monitor the radio threads --- flight/Modules/Radio/radio.c | 5 +++++ shared/uavobjectdefinition/taskinfo.xml | 6 +++--- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 6df334fae..bb9e5a993 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -139,6 +139,11 @@ static int32_t RadioStart(void) xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); xTaskCreate(sendPacketTask, (signed char *)"SendPacket", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle)); + // Install the monitors + TaskMonitorAdd(TASKINFO_RUNNING_MODEMRX, data->radioReceiveTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_MODEMTX, data->sendPacketTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_MODEMSTAT, data->radioStatusTaskHandle); + // Register the watchdog timers. #ifdef PIOS_WDG_RADIORECEIVE PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE); diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 8ab53da0d..355a1b1a2 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + + From 3a3fc3d1246e52fcc068e635cb61532de5030b05 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 18:48:41 -0500 Subject: [PATCH 399/508] Make the radio module builtin --- flight/RevoMini/Makefile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index 06dd2228f..2675ecc61 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -63,6 +63,8 @@ MODULES += Telemetry PYMODULES = #FlightPlan +CFLAGS += -DRADIO_BUILTIN + # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc From 4014445cc90b9d4a99d03509e5e7d42e334a77a2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 19:10:16 -0500 Subject: [PATCH 400/508] Fix the IRQ line for the RFM22b --- flight/board_hw_defs/revomini/board_hw_defs.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 0a33a6ebb..51fa21eee 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -321,11 +321,11 @@ void PIOS_SPI_telem_flash_irq_handler(void) static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { .vector = PIOS_RFM22_EXT_Int, - .line = EXTI_Line0, + .line = EXTI_Line2, .pin = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_0, + .GPIO_Pin = GPIO_Pin_2, .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, @@ -334,7 +334,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { }, .irq = { .init = { - .NVIC_IRQChannel = EXTI0_IRQn, + .NVIC_IRQChannel = EXTI2_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, @@ -342,7 +342,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { }, .exti = { .init = { - .EXTI_Line = EXTI_Line0, // matches above GPIO pin + .EXTI_Line = EXTI_Line2, // matches above GPIO pin .EXTI_Mode = EXTI_Mode_Interrupt, .EXTI_Trigger = EXTI_Trigger_Falling, .EXTI_LineCmd = ENABLE, From 69cd7235d3cfdf9dc8aad6d2be35f19c0edff32c Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 22 Aug 2012 04:49:26 +1000 Subject: [PATCH 401/508] Change Default GPS protocol to UBX --- shared/uavobjectdefinition/gpssettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/gpssettings.xml b/shared/uavobjectdefinition/gpssettings.xml index 5c38f43fe..af58793d1 100644 --- a/shared/uavobjectdefinition/gpssettings.xml +++ b/shared/uavobjectdefinition/gpssettings.xml @@ -1,7 +1,7 @@ Settings for the GPS - + From 06154836c6cb5ba89e37907571115b9edb913db9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 19:31:48 -0500 Subject: [PATCH 402/508] Define the RADIO_BUILTIN in config file --- flight/RevoMini/Makefile | 2 -- flight/RevoMini/System/inc/pios_config.h | 3 ++- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index 2675ecc61..06dd2228f 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -63,8 +63,6 @@ MODULES += Telemetry PYMODULES = #FlightPlan -CFLAGS += -DRADIO_BUILTIN - # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index eb282fdd8..552a1cbbd 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -60,7 +60,8 @@ #define PIOS_INCLUDE_RFM22B #define PIOS_INCLUDE_PACKET_HANDLER #define RFM22_EXT_INT_USE - +#define RADIO_BUILTIN + /* Select the sensors to include */ #define PIOS_INCLUDE_HMC5883 #define PIOS_INCLUDE_MPU6000 From 524540895fcda3e067ae244a79fe4a91f05d6839 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 19:32:06 -0500 Subject: [PATCH 403/508] Never ask if there are other devices to enumerate. We don't do that anymore for any active boards. --- .../plugins/uploader/uploadergadgetwidget.cpp | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 4827ce4a7..e79e0be69 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -523,25 +523,6 @@ void UploaderGadgetWidget::systemRescue() m_config->rescueButton->setEnabled(true); return; } - if ((dfu->GetBoardType(0) != eBoardRevo) && (eBoardCC != dfu->GetBoardType(0)) && (QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes)) - { - log("\nWaiting..."); - QTimer::singleShot(3000, &m_eventloop, SLOT(quit())); - m_eventloop.exec(); - log("Detecting second board..."); - repaint(); - if(!dfu->findDevices()) - { - // We will only end up here in case somehow all the boards - // disappeared, including the one we detected earlier. - log("Could not detect any board, aborting!"); - delete dfu; - dfu = NULL; - cm->resumePolling(); - m_config->rescueButton->setEnabled(true); - return; - } - } log(QString("Found ") + QString::number(dfu->numberOfDevices) + QString(" device(s).")); if (dfu->numberOfDevices > 5) { log("Inconsistent number of devices, aborting!"); From 446870d8692941300cfaa4e52400b6ff0c29e34e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 19:37:50 -0500 Subject: [PATCH 404/508] TxPID: Set the timeOut to NULL after deleting it. I had a segfault from here. --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7736ba00e..09d6e21a5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -180,6 +180,7 @@ ConfigTaskWidget::~ConfigTaskWidget() if(timeOut) { delete timeOut; + timeOut = NULL; } } From b08775666bc614ec4eb8ba304bf2697d084fdfb3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 22:12:41 -0500 Subject: [PATCH 405/508] Disable the telemetry port by default --- shared/uavobjectdefinition/hwsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 862e8514a..052c011eb 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -9,7 +9,7 @@ - + From 2bb4f860e1872cb512c8401ee2a0fd895907c483 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 22:34:13 -0500 Subject: [PATCH 406/508] Shuffle around the PACKET_HANDLER definition so we can more easily disable the Radio module. --- flight/PiOS/Boards/STM32F4xx_RevoMini.h | 8 +++----- flight/RevoMini/System/inc/pios_config.h | 1 - 2 files changed, 3 insertions(+), 6 deletions(-) diff --git a/flight/PiOS/Boards/STM32F4xx_RevoMini.h b/flight/PiOS/Boards/STM32F4xx_RevoMini.h index 36f5f1d0d..dfec89387 100644 --- a/flight/PiOS/Boards/STM32F4xx_RevoMini.h +++ b/flight/PiOS/Boards/STM32F4xx_RevoMini.h @@ -147,14 +147,12 @@ extern uint32_t pios_spi_telem_flash_id; //------------------------- // Packet Handler //------------------------- -#if defined(PIOS_INCLUDE_PACKET_HANDLER) -extern uint32_t pios_packet_handler; -#define PIOS_PACKET_HANDLER (pios_packet_handler) +#define RS_ECC_NPARITY 4 #define PIOS_PH_MAX_PACKET 255 #define PIOS_PH_WIN_SIZE 3 #define PIOS_PH_MAX_CONNECTIONS 1 -#define RS_ECC_NPARITY 4 -#endif /* PIOS_INCLUDE_PACKET_HANDLER */ +extern uint32_t pios_packet_handler; +#define PIOS_PACKET_HANDLER (pios_packet_handler) //------------------------ // TELEMETRY diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 552a1cbbd..9b1bbb554 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -58,7 +58,6 @@ /* Variables related to the RFM22B functionality */ #define PIOS_INCLUDE_RFM22B -#define PIOS_INCLUDE_PACKET_HANDLER #define RFM22_EXT_INT_USE #define RADIO_BUILTIN From 84d327c46ac7377e51dd805facaa49cf2ff6c046 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 23:07:00 -0500 Subject: [PATCH 407/508] RFM22b: Claim the bus semaphore before reading and writing. --- flight/PiOS/Common/pios_rfm22b.c | 41 +++++++++++++++++--------------- 1 file changed, 22 insertions(+), 19 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 17c385c3e..d03f1bec5 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -642,21 +642,33 @@ static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id) // ************************************ // SPI read/write +static void rfm22_claimBus() +{ + // chip select line LOW + PIOS_SPI_ClaimBus(PIOS_RFM22_SPI_PORT); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); +} + +static void rfm22_releaseBus() +{ + // chip select line HIGH + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + PIOS_SPI_ReleaseBus(PIOS_RFM22_SPI_PORT); +} + void rfm22_startBurstWrite(uint8_t addr) { // wait 1us .. so we don't toggle the CS line to quickly PIOS_DELAY_WaituS(1); - // chip select line LOW - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + rfm22_claimBus(); PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); } void rfm22_endBurstWrite(void) { - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_releaseBus(); } void rfm22_write(uint8_t addr, uint8_t data) @@ -664,14 +676,12 @@ void rfm22_write(uint8_t addr, uint8_t data) // wait 1us .. so we don't toggle the CS line to quickly PIOS_DELAY_WaituS(1); - // chip select line LOW - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + rfm22_claimBus(); PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, data); - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_releaseBus(); } void rfm22_startBurstRead(uint8_t addr) @@ -679,16 +689,14 @@ void rfm22_startBurstRead(uint8_t addr) // wait 1us .. so we don't toggle the CS line to quickly PIOS_DELAY_WaituS(1); - // chip select line LOW - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + rfm22_claimBus(); PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); } void rfm22_endBurstRead(void) { - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_releaseBus(); } uint8_t rfm22_read(uint8_t addr) @@ -698,14 +706,12 @@ uint8_t rfm22_read(uint8_t addr) // wait 1us .. so we don't toggle the CS line to quickly PIOS_DELAY_WaituS(1); - // chip select line LOW - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + rfm22_claimBus(); PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); rdata = PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_releaseBus(); return rdata; } @@ -1764,9 +1770,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // **************** // setup the SPI port - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); - // set SPI port SCLK frequency .. 4.5MHz PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_16); // set SPI port SCLK frequency .. 2.25MHz From 27c46c78b2cbcae1b7351dfe44e6d4378f6483d7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 23:09:25 -0500 Subject: [PATCH 408/508] Increase the RFM22b/Flash rate to 10MHz which is within tolerance for both. --- flight/board_hw_defs/revomini/board_hw_defs.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 51fa21eee..ba8205310 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -202,7 +202,7 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { .SPI_CRCPolynomial = 7, .SPI_CPOL = SPI_CPOL_Low, .SPI_CPHA = SPI_CPHA_1Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, }, .use_crc = false, .dma = { From 144fea1bd12615bc49c76c60fbdf8d63ef6a8e83 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 25 Aug 2012 23:46:40 -0400 Subject: [PATCH 409/508] gcs: fix pipx-related typos in GCS This also fixes the auto-selecting of FW images for pipx in the uploader GUI by making the board name match fw_pipxtreme. --- ground/openpilotgcs/src/plugins/config/pipxtreme.ui | 2 +- .../src/plugins/uavobjectutil/devicedescriptorstruct.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index 9de1a7120..89616441b 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -1612,7 +1612,7 @@ - AES Encription + AES Encryption diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h index 496448dd6..62add4d18 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h @@ -20,7 +20,7 @@ public: return QString("OpenPilot INS"); break; case 0x0301://PipX - return QString("PipXtreame"); + return QString("PipXtreme"); break; case 0x0401://Coptercontrol return QString("CopterControl"); From 001c43c0906f2900f5587591a380f34db4cbc651 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 23:44:58 -0500 Subject: [PATCH 410/508] Increase timeout to shut down the telemetry threads. Might fix some OSX USB related crashes. --- ground/openpilotgcs/src/plugins/rawhid/rawhid.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/rawhid/rawhid.cpp b/ground/openpilotgcs/src/plugins/rawhid/rawhid.cpp index 4649d6162..b26069702 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/rawhid.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/rawhid.cpp @@ -144,7 +144,7 @@ RawHIDReadThread::~RawHIDReadThread() { m_running = false; //wait for the thread to terminate - if(wait(1000) == false) + if(wait(10000) == false) qDebug() << "Cannot terminate RawHIDReadThread"; } @@ -216,8 +216,8 @@ RawHIDWriteThread::~RawHIDWriteThread() { m_running = false; //wait for the thread to terminate - if(wait(1000) == false) - qDebug() << "Cannot terminate RawHIDReadThread"; + if(wait(10000) == false) + qDebug() << "Cannot terminate RawHIDWriteThread"; } void RawHIDWriteThread::run() From b1bd6d8583e9fb960f77940b5b095420b40dd8f9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 23:59:07 -0500 Subject: [PATCH 411/508] PIOS_RFM22b: No need to set the SPI clock speed in the RFM22b module - it can be set by the driver configuration. --- flight/PiOS/Common/pios_rfm22b.c | 11 ----------- flight/board_hw_defs/pipxtreme/board_hw_defs.c | 2 +- 2 files changed, 1 insertion(+), 12 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index d03f1bec5..bf6704a1b 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1767,17 +1767,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq exec_using_spi = true; - // **************** - // setup the SPI port - - // set SPI port SCLK frequency .. 4.5MHz - PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_16); - // set SPI port SCLK frequency .. 2.25MHz - // PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_32); - - // set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding - // PIOS_SPI_SetClockSpeed(PIOS_RFM22_SPI_PORT, PIOS_SPI_PRESCALER_256); - // **************** // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index 5550b8ffd..30c666f17 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -86,7 +86,7 @@ static const struct pios_spi_cfg pios_spi_rfm22b_cfg = .SPI_CRCPolynomial = 0, .SPI_CPOL = SPI_CPOL_Low, .SPI_CPHA = SPI_CPHA_1Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, // slowest SCLK + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, // slowest SCLK }, .use_crc = FALSE, From 477385ca2583a10d098d585c0cfade69e211aafb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 02:41:19 -0500 Subject: [PATCH 412/508] RFM22b: Start to move the ISR into userspace --- flight/Modules/Radio/radio.c | 2 +- flight/PiOS/Common/pios_rfm22b.c | 47 +++++++++++++++++++++++++++++--- flight/PiOS/inc/pios_rfm22b.h | 1 + 3 files changed, 45 insertions(+), 5 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index bb9e5a993..0bc15bf76 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -321,7 +321,7 @@ static void radioReceiveTask(void *parameters) if(p == NULL) { // Wait a bit for a packet to come available. - vTaskDelay(5); + PIOS_RFM22_processPendingISR(5); continue; } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index bf6704a1b..654fdace5 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -162,6 +162,9 @@ struct pios_rfm22b_dev { uint32_t deviceID; + // ISR pending + xSemaphoreHandle isrPending; + // The COM callback functions. pios_com_callback rx_in_cb; uint32_t rx_in_context; @@ -277,7 +280,7 @@ const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 volatile bool initialized = false; #if defined(RFM22_EXT_INT_USE) -volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt +volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt #endif uint8_t device_type; // the RF chips device ID number @@ -397,6 +400,8 @@ static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) } #endif +static struct pios_rfm22b_dev * g_rfm22b_dev; + /** * Initialise an RFM22B device */ @@ -414,6 +419,10 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) rfm22b_dev->cfg = *cfg; *rfm22b_id = (uint32_t)rfm22b_dev; + g_rfm22b_dev = rfm22b_dev; + + // Create a semaphore to know if an ISR needs responding to + vSemaphoreCreateBinary( rfm22b_dev->isrPending ); // Initialize the TX pre-buffer pointer. tx_pre_buffer_size = 0; @@ -719,13 +728,43 @@ uint8_t rfm22_read(uint8_t addr) // ************************************ // external interrupt - +uint32_t rfm32_errors; +uint32_t rfm32_irqs_processed; +uint32_t rfm32_irqs_processedv2; +volatile bool pending; void PIOS_RFM22_EXT_Int(void) { - if (!exec_using_spi) - rfm22_processInt(); + bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); + PIOS_Assert(valid); + + portBASE_TYPE pxHigherPriorityTaskWoken; + if (!exec_using_spi) { + if (xSemaphoreGiveFromISR(g_rfm22b_dev->isrPending, &pxHigherPriorityTaskWoken) != pdTRUE) { + // Something went fairly seriously wrong + rfm32_errors++; + } + portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); + } + + pending = true; } +void PIOS_RFM22_processPendingISR(uint32_t wait_ms) +{ + bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); + PIOS_Assert(valid); + + if ( xSemaphoreTake(g_rfm22b_dev->isrPending, wait_ms / portTICK_RATE_MS) == pdTRUE ) { + rfm32_irqs_processed++; + rfm22_processInt(); + } + + if (pending) { + rfm32_irqs_processedv2++; + rfm22_processInt(); + pending = false; + } +} // ************************************ // set/get the current tx power setting diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index df9b6aa9e..31b33a69d 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -48,6 +48,7 @@ extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, const struct pios_rfm22b_cf extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); +extern void PIOS_RFM22_processPendingISR(uint32_t wait_ms); #endif /* PIOS_RFM22B_H */ From f7cda1c0c426fe1ccdfd63a54f2293cca44a5ce1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 02:42:18 -0500 Subject: [PATCH 413/508] RFM22b: No need to initialize the SPI. Done already. --- flight/PiOS/Common/pios_rfm22b.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 654fdace5..60e5cd0f4 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -443,11 +443,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; rfm22b_dev->resets = 0; - // Initialize our SPI interface - if (PIOS_SPI_Init(&PIOS_RFM22_SPI_PORT, cfg->spi_cfg)) { - PIOS_Assert(0); - } - // Initialize the external interrupt. PIOS_EXTI_Init(cfg->exti_cfg); From 042055b29af7a3ab5ecc652a8d37ba7c20e9cb81 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 02:53:44 -0500 Subject: [PATCH 414/508] RFM22b: Call the pendingISR routine from all the user space tasks. Got a valid connection with this. --- flight/Modules/Radio/radio.c | 8 +++++--- flight/PiOS/Common/pios_rfm22b.c | 11 +---------- 2 files changed, 6 insertions(+), 13 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 0bc15bf76..6055e38d8 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -315,13 +315,15 @@ static void radioReceiveTask(void *parameters) PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); #endif /* PIOS_INCLUDE_WDG */ + PIOS_RFM22_processPendingISR(5); + // Get a RX packet from the packet handler if required. if (p == NULL) p = PHGetRXPacket(pios_packet_handler); if(p == NULL) { // Wait a bit for a packet to come available. - PIOS_RFM22_processPendingISR(5); + vTaskDelay(5); continue; } @@ -522,8 +524,8 @@ static void radioStatusTask(void *parameters) } } - // Delay until the next update period. - vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); + for(int i = 0; i < 20; i++) + PIOS_RFM22_processPendingISR(5); } } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 60e5cd0f4..8d35bf917 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -725,8 +725,7 @@ uint8_t rfm22_read(uint8_t addr) uint32_t rfm32_errors; uint32_t rfm32_irqs_processed; -uint32_t rfm32_irqs_processedv2; -volatile bool pending; + void PIOS_RFM22_EXT_Int(void) { bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); @@ -740,8 +739,6 @@ void PIOS_RFM22_EXT_Int(void) } portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); } - - pending = true; } void PIOS_RFM22_processPendingISR(uint32_t wait_ms) @@ -753,12 +750,6 @@ void PIOS_RFM22_processPendingISR(uint32_t wait_ms) rfm32_irqs_processed++; rfm22_processInt(); } - - if (pending) { - rfm32_irqs_processedv2++; - rfm22_processInt(); - pending = false; - } } // ************************************ From b888a137f09df9ba5c4b5bfd17660d5b1e85e95f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 05:02:14 -0500 Subject: [PATCH 415/508] TOFIX: Temporarily remove the transaction lock from the settings as it was causing a deadlock with the radio coms. --- flight/PiOS/Common/pios_flash_jedec.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/PiOS/Common/pios_flash_jedec.c b/flight/PiOS/Common/pios_flash_jedec.c index 4af779f1a..4455f06ff 100644 --- a/flight/PiOS/Common/pios_flash_jedec.c +++ b/flight/PiOS/Common/pios_flash_jedec.c @@ -196,6 +196,7 @@ int32_t PIOS_Flash_Jedec_Init(uint32_t spi_id, uint32_t slave_num, const struct */ int32_t PIOS_Flash_Jedec_StartTransaction() { + return 0; #if defined(FLASH_FREERTOS) if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) return -1; @@ -212,6 +213,7 @@ int32_t PIOS_Flash_Jedec_StartTransaction() */ int32_t PIOS_Flash_Jedec_EndTransaction() { + return 0; #if defined(FLASH_FREERTOS) if(PIOS_Flash_Jedec_Validate(flash_dev) != 0) return -1; From bdd50ce66b6eef2000f57c61e863883a762fd15c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 05:03:05 -0500 Subject: [PATCH 416/508] Reenable the flash system --- flight/RevoMini/System/pios_board.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index e5f870e2f..1fc2eaa8a 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -309,8 +309,8 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_FLASH) /* Connect flash to the approrpiate interface and configure it */ - //PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 1, &flash_m25p_cfg); - //PIOS_FLASHFS_Init(&flashfs_m25p_cfg); + PIOS_Flash_Jedec_Init(pios_spi_telem_flash_id, 1, &flash_m25p_cfg); + PIOS_FLASHFS_Init(&flashfs_m25p_cfg); #endif /* Initialize UAVObject libraries */ From 6b3934576aa955ff8e61e506a520c4c5d0dc0240 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sun, 26 Aug 2012 08:37:08 -0700 Subject: [PATCH 417/508] Fixed configuration of PipX com port as UAVTalk. --- flight/Modules/RadioComBridge/RadioComBridge.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 8a92e27ee..188f5f974 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -245,7 +245,7 @@ static int32_t RadioComBridgeInitialize(void) // Initialize the UAVTalk comm parameters. data->gcs_uavtalk_params.isGCS = true; data->gcs_uavtalk_params.UAVTalkCon = data->GCSUAVTalkCon; - data->gcs_uavtalk_params.sendQueue = data->UAVTalkCon; + data->gcs_uavtalk_params.sendQueue = data->uavtalkEventQueue; data->gcs_uavtalk_params.recvQueue = data->gcsEventQueue; data->gcs_uavtalk_params.wdg = PIOS_WDG_COMGCS; data->gcs_uavtalk_params.comPort = PIOS_COM_GCS; @@ -253,7 +253,7 @@ static int32_t RadioComBridgeInitialize(void) { data->uavtalk_params.isGCS = false; data->uavtalk_params.UAVTalkCon = data->UAVTalkCon; - data->uavtalk_params.sendQueue = data->GCSUAVTalkCon; + data->uavtalk_params.sendQueue = data->gcsEventQueue; data->uavtalk_params.recvQueue = data->uavtalkEventQueue; data->uavtalk_params.wdg = PIOS_WDG_COMUAVTALK; data->uavtalk_params.comPort = PIOS_COM_UAVTALK; From d2a12d8bd568affae8bbdf6033f5a0041f00d944 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:04:40 -0500 Subject: [PATCH 418/508] AndroidGCS: Clean up some warnings from OsgViewer --- .../org/openpilot/androidgcs/OsgViewer.java | 58 ++----------------- 1 file changed, 4 insertions(+), 54 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java index 9928b19cf..be4d507c2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java +++ b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java @@ -10,11 +10,9 @@ import android.graphics.Color; import android.graphics.PointF; import android.os.Bundle; import android.os.Environment; +import android.util.FloatMath; import android.util.Log; import android.view.KeyEvent; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.MotionEvent; import android.view.View; import android.view.View.OnClickListener; @@ -79,12 +77,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList uiLightChangeButton = (Button) findViewById(R.id.uiButtonLight); uiLightChangeButton.setOnClickListener(uiListenerChangeLight); - //Creating Toasts - msgUiNavPrincipal = Toast.makeText(getApplicationContext(), "toast1", Toast.LENGTH_SHORT); - msgUiNavSecondary = Toast.makeText(getApplicationContext(), "toast2", Toast.LENGTH_SHORT); - msgUiLightOn = Toast.makeText(getApplicationContext(), "toast3", Toast.LENGTH_SHORT); - msgUiLightOff = Toast.makeText(getApplicationContext(), "toast4", Toast.LENGTH_SHORT); - String address = Environment.getExternalStorageDirectory().getPath() + "/Models/J14-QT_X.3DS"; //quad.osg"; Log.d(TAG, "Address: " + address); osgNativeLib.loadObject(address); @@ -135,7 +127,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList //dumpEvent(event); - long time_arrival = event.getEventTime(); int n_points = event.getPointerCount(); int action = event.getAction() & MotionEvent.ACTION_MASK; @@ -204,6 +195,8 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList else osgNativeLib.mouseButtonReleaseEvent(event.getX(0), event.getY(0), 1); break; + default: + break; } mode = moveTypes.ZOOM; distanceOrigin = sqrDistance(event); @@ -299,53 +292,10 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList osgNativeLib.setClearColor(red,green,blue); } - //Android Life Cycle Menu - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); -// inflater.inflate(R.menu.appmenu, menu); - return super.onCreateOptionsMenu(menu); - } - @Override - public boolean onOptionsItemSelected(MenuItem item) { - // Handle item selection - switch (item.getItemId()) { - default: - return super.onOptionsItemSelected(item); - } - } - - //Utilities - /** Show an event in the LogCat view, for debugging */ - private void dumpEvent(MotionEvent event) { - String names[] = { "DOWN", "UP", "MOVE", "CANCEL", "OUTSIDE", - "POINTER_DOWN", "POINTER_UP", "7?", "8?", "9?" }; - StringBuilder sb = new StringBuilder(); - int action = event.getAction(); - int actionCode = action & MotionEvent.ACTION_MASK; - sb.append("event ACTION_").append(names[actionCode]); - if (actionCode == MotionEvent.ACTION_POINTER_DOWN - || actionCode == MotionEvent.ACTION_POINTER_UP) { - sb.append("(pid ").append( - action >> MotionEvent.ACTION_POINTER_ID_SHIFT); - sb.append(")"); - } - sb.append("["); - for (int i = 0; i < event.getPointerCount(); i++) { - sb.append("#").append(i); - sb.append("(pid ").append(event.getPointerId(i)); - sb.append(")=").append((int) event.getX(i)); - sb.append(",").append((int) event.getY(i)); - if (i + 1 < event.getPointerCount()) - sb.append(";"); - } - sb.append("]"); - //Log.d(TAG, sb.toString()); - } private float sqrDistance(MotionEvent event) { float x = event.getX(0) - event.getX(1); float y = event.getY(0) - event.getY(1); - return (float)(Math.sqrt(x * x + y * y)); + return (float)(FloatMath.sqrt(x * x + y * y)); } // The below methods should all be called by the parent activity at the appropriate times From d61a649491079e181d2d7604463df62f8000f2e6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:05:53 -0500 Subject: [PATCH 419/508] AndroidGCS: Suppress some warnings from Controller.java --- androidgcs/src/org/openpilot/androidgcs/Controller.java | 1 - 1 file changed, 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/Controller.java b/androidgcs/src/org/openpilot/androidgcs/Controller.java index 0d3a3c911..39a86639c 100644 --- a/androidgcs/src/org/openpilot/androidgcs/Controller.java +++ b/androidgcs/src/org/openpilot/androidgcs/Controller.java @@ -70,7 +70,6 @@ public class Controller extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.controller); - TextView manualView = (TextView) findViewById(R.id.manualControlValues); } Observer settingsUpdated = new Observer() { From 05fd56ede50015b2c01c9afb7ab1c724299beb9e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:26:34 -0500 Subject: [PATCH 420/508] AndroidGCS: Suppress some warnings related to not implementing the STRING uavfield type properly. --- .../openpilot/androidgcs/ObjectEditView.java | 26 ++++++++++++------- .../org/openpilot/uavtalk/UAVObjectField.java | 25 +++++++++++------- 2 files changed, 32 insertions(+), 19 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java index 7946a357b..401a26978 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -22,22 +22,22 @@ public class ObjectEditView extends GridLayout { public List fields; public ObjectEditView(Context context) { - super(context); + super(context); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { super(context, ats); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats) { + public ObjectEditView(Context context, AttributeSet ats) { super(context, ats); initObjectEditView(); } public void initObjectEditView() { - // Set orientation of layout to vertical + // Set orientation of layout to vertical setOrientation(LinearLayout.VERTICAL); setColumnCount(2); fields = new ArrayList(); @@ -51,11 +51,11 @@ public class ObjectEditView extends GridLayout { for (int i = 0; i < field.getNumElements(); i++) addRow(getContext(), field, i); } - - + + public void addRow(Context context, UAVObjectField field, int idx) { int row = getRowCount(); - + TextView fieldName = new TextView(context); if(field.getNumElements() == 1) { fieldName.setText(field.getName()); @@ -65,7 +65,7 @@ public class ObjectEditView extends GridLayout { addView(fieldName, new GridLayout.LayoutParams(spec(row), spec(0))); View fieldValue = null; - switch(field.getType()) + switch(field.getType()) { case FLOAT32: fieldValue = new EditText(context); @@ -93,8 +93,16 @@ public class ObjectEditView extends GridLayout { ((Spinner) fieldValue).setAdapter(adapter); ((Spinner) fieldValue).setSelection((int) field.getDouble(idx)); break; + case BITFIELD: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); + ((EditText)fieldValue).setInputType(InputType.TYPE_CLASS_NUMBER); + break; + case STRING: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); } - + addView(fieldValue, new GridLayout.LayoutParams(spec(row), spec(1))); fields.add(fieldValue); } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d07fdf6fd..7fea950f0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -578,6 +578,12 @@ public class UAVObjectField { ((ArrayList) data).add((byte) 0); } break; + case STRING: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -633,7 +639,7 @@ public class UAVObjectField { numBytesPerElement = 1; break; case STRING: - data = new ArrayList(this.numElements); + data = new ArrayList(this.numElements); numBytesPerElement = 1; break; default: @@ -650,15 +656,9 @@ public class UAVObjectField { */ protected Long bound (Object val) { - switch(type) { - case ENUM: - case STRING: - return 0L; - case FLOAT32: - return ((Number) val).longValue(); - } - - long num = ((Number) val).longValue(); + long num = 0; + if (isNumeric()) + num = ((Number) val).longValue(); switch(type) { case INT8: @@ -703,6 +703,11 @@ public class UAVObjectField { if(num > 255) return (long) 255; return num; + case FLOAT32: + return ((Number) val).longValue(); + case ENUM: + case STRING: + return 0L; } return num; From e68603ac6a530ee686799b6e30f27a0a5e247d91 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 09:53:23 -0500 Subject: [PATCH 421/508] AndroidGCS: Make sure the telemetry sevice checks there is a telemetry task AND it's connected before sending the OPConnected service. Otherwise the objMngr is undefined. --- .../org/openpilot/androidgcs/telemetry/OPTelemetryService.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java index 4698900ef..88cb9a632 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java @@ -258,7 +258,7 @@ public class OPTelemetryService extends Service { mServiceHandler.sendMessage(msg); } public boolean isConnected() { - return activeTelem != null; + return (activeTelem != null) && (telemTask != null) && (telemTask.getConnected()); } }; From 882f23b344fe048fc1fca2c490385691c646187c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:04:40 -0500 Subject: [PATCH 422/508] AndroidGCS: Clean up some warnings from OsgViewer --- .../org/openpilot/androidgcs/OsgViewer.java | 58 ++----------------- 1 file changed, 4 insertions(+), 54 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java index 9928b19cf..be4d507c2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java +++ b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java @@ -10,11 +10,9 @@ import android.graphics.Color; import android.graphics.PointF; import android.os.Bundle; import android.os.Environment; +import android.util.FloatMath; import android.util.Log; import android.view.KeyEvent; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.MotionEvent; import android.view.View; import android.view.View.OnClickListener; @@ -79,12 +77,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList uiLightChangeButton = (Button) findViewById(R.id.uiButtonLight); uiLightChangeButton.setOnClickListener(uiListenerChangeLight); - //Creating Toasts - msgUiNavPrincipal = Toast.makeText(getApplicationContext(), "toast1", Toast.LENGTH_SHORT); - msgUiNavSecondary = Toast.makeText(getApplicationContext(), "toast2", Toast.LENGTH_SHORT); - msgUiLightOn = Toast.makeText(getApplicationContext(), "toast3", Toast.LENGTH_SHORT); - msgUiLightOff = Toast.makeText(getApplicationContext(), "toast4", Toast.LENGTH_SHORT); - String address = Environment.getExternalStorageDirectory().getPath() + "/Models/J14-QT_X.3DS"; //quad.osg"; Log.d(TAG, "Address: " + address); osgNativeLib.loadObject(address); @@ -135,7 +127,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList //dumpEvent(event); - long time_arrival = event.getEventTime(); int n_points = event.getPointerCount(); int action = event.getAction() & MotionEvent.ACTION_MASK; @@ -204,6 +195,8 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList else osgNativeLib.mouseButtonReleaseEvent(event.getX(0), event.getY(0), 1); break; + default: + break; } mode = moveTypes.ZOOM; distanceOrigin = sqrDistance(event); @@ -299,53 +292,10 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList osgNativeLib.setClearColor(red,green,blue); } - //Android Life Cycle Menu - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); -// inflater.inflate(R.menu.appmenu, menu); - return super.onCreateOptionsMenu(menu); - } - @Override - public boolean onOptionsItemSelected(MenuItem item) { - // Handle item selection - switch (item.getItemId()) { - default: - return super.onOptionsItemSelected(item); - } - } - - //Utilities - /** Show an event in the LogCat view, for debugging */ - private void dumpEvent(MotionEvent event) { - String names[] = { "DOWN", "UP", "MOVE", "CANCEL", "OUTSIDE", - "POINTER_DOWN", "POINTER_UP", "7?", "8?", "9?" }; - StringBuilder sb = new StringBuilder(); - int action = event.getAction(); - int actionCode = action & MotionEvent.ACTION_MASK; - sb.append("event ACTION_").append(names[actionCode]); - if (actionCode == MotionEvent.ACTION_POINTER_DOWN - || actionCode == MotionEvent.ACTION_POINTER_UP) { - sb.append("(pid ").append( - action >> MotionEvent.ACTION_POINTER_ID_SHIFT); - sb.append(")"); - } - sb.append("["); - for (int i = 0; i < event.getPointerCount(); i++) { - sb.append("#").append(i); - sb.append("(pid ").append(event.getPointerId(i)); - sb.append(")=").append((int) event.getX(i)); - sb.append(",").append((int) event.getY(i)); - if (i + 1 < event.getPointerCount()) - sb.append(";"); - } - sb.append("]"); - //Log.d(TAG, sb.toString()); - } private float sqrDistance(MotionEvent event) { float x = event.getX(0) - event.getX(1); float y = event.getY(0) - event.getY(1); - return (float)(Math.sqrt(x * x + y * y)); + return (float)(FloatMath.sqrt(x * x + y * y)); } // The below methods should all be called by the parent activity at the appropriate times From 89997de1cc02ed9256af482e45573f4366a888ff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:05:53 -0500 Subject: [PATCH 423/508] AndroidGCS: Suppress some warnings from Controller.java --- androidgcs/src/org/openpilot/androidgcs/Controller.java | 1 - 1 file changed, 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/Controller.java b/androidgcs/src/org/openpilot/androidgcs/Controller.java index 0d3a3c911..39a86639c 100644 --- a/androidgcs/src/org/openpilot/androidgcs/Controller.java +++ b/androidgcs/src/org/openpilot/androidgcs/Controller.java @@ -70,7 +70,6 @@ public class Controller extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.controller); - TextView manualView = (TextView) findViewById(R.id.manualControlValues); } Observer settingsUpdated = new Observer() { From c2e55ecc21c49b10486b3c53b09e0cb8e77395a0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:26:34 -0500 Subject: [PATCH 424/508] AndroidGCS: Suppress some warnings related to not implementing the STRING uavfield type properly. --- .../openpilot/androidgcs/ObjectEditView.java | 26 ++++++++++++------- .../org/openpilot/uavtalk/UAVObjectField.java | 25 +++++++++++------- 2 files changed, 32 insertions(+), 19 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java index 7946a357b..401a26978 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -22,22 +22,22 @@ public class ObjectEditView extends GridLayout { public List fields; public ObjectEditView(Context context) { - super(context); + super(context); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { super(context, ats); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats) { + public ObjectEditView(Context context, AttributeSet ats) { super(context, ats); initObjectEditView(); } public void initObjectEditView() { - // Set orientation of layout to vertical + // Set orientation of layout to vertical setOrientation(LinearLayout.VERTICAL); setColumnCount(2); fields = new ArrayList(); @@ -51,11 +51,11 @@ public class ObjectEditView extends GridLayout { for (int i = 0; i < field.getNumElements(); i++) addRow(getContext(), field, i); } - - + + public void addRow(Context context, UAVObjectField field, int idx) { int row = getRowCount(); - + TextView fieldName = new TextView(context); if(field.getNumElements() == 1) { fieldName.setText(field.getName()); @@ -65,7 +65,7 @@ public class ObjectEditView extends GridLayout { addView(fieldName, new GridLayout.LayoutParams(spec(row), spec(0))); View fieldValue = null; - switch(field.getType()) + switch(field.getType()) { case FLOAT32: fieldValue = new EditText(context); @@ -93,8 +93,16 @@ public class ObjectEditView extends GridLayout { ((Spinner) fieldValue).setAdapter(adapter); ((Spinner) fieldValue).setSelection((int) field.getDouble(idx)); break; + case BITFIELD: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); + ((EditText)fieldValue).setInputType(InputType.TYPE_CLASS_NUMBER); + break; + case STRING: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); } - + addView(fieldValue, new GridLayout.LayoutParams(spec(row), spec(1))); fields.add(fieldValue); } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d07fdf6fd..7fea950f0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -578,6 +578,12 @@ public class UAVObjectField { ((ArrayList) data).add((byte) 0); } break; + case STRING: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -633,7 +639,7 @@ public class UAVObjectField { numBytesPerElement = 1; break; case STRING: - data = new ArrayList(this.numElements); + data = new ArrayList(this.numElements); numBytesPerElement = 1; break; default: @@ -650,15 +656,9 @@ public class UAVObjectField { */ protected Long bound (Object val) { - switch(type) { - case ENUM: - case STRING: - return 0L; - case FLOAT32: - return ((Number) val).longValue(); - } - - long num = ((Number) val).longValue(); + long num = 0; + if (isNumeric()) + num = ((Number) val).longValue(); switch(type) { case INT8: @@ -703,6 +703,11 @@ public class UAVObjectField { if(num > 255) return (long) 255; return num; + case FLOAT32: + return ((Number) val).longValue(); + case ENUM: + case STRING: + return 0L; } return num; From e6ccfb9c610db12c14cf47fcc169e5cfc14754ad Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 09:53:23 -0500 Subject: [PATCH 425/508] AndroidGCS: Make sure the telemetry sevice checks there is a telemetry task AND it's connected before sending the OPConnected service. Otherwise the objMngr is undefined. --- .../org/openpilot/androidgcs/telemetry/OPTelemetryService.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java index 4698900ef..88cb9a632 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java @@ -258,7 +258,7 @@ public class OPTelemetryService extends Service { mServiceHandler.sendMessage(msg); } public boolean isConnected() { - return activeTelem != null; + return (activeTelem != null) && (telemTask != null) && (telemTask.getConnected()); } }; From 57cf7c67a63982d3f50012fe64215ed5953dfff7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 11:05:08 -0500 Subject: [PATCH 426/508] AndroidGCS PFD: Properly center image now so it works over multiple sizes. However, it doesn't automatically fill the screen in normal PFD view yet. Specifying the width in pfd.xml directly does fix that but is incorrect. --- .../openpilot/androidgcs/AttitudeView.java | 26 ++++++++++++------- .../org/openpilot/androidgcs/PfdActivity.java | 5 ++-- 2 files changed, 19 insertions(+), 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java index d8aecc5e1..3bf0e5227 100644 --- a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -93,25 +93,33 @@ public class AttitudeView extends View { @Override protected void onDraw(Canvas canvas) { - final int PX = getMeasuredWidth() / 2; - final int PY = getMeasuredHeight() / 2; + final int PX = getMeasuredWidth(); + final int PY = getMeasuredHeight(); - // TODO: Figure out why these magic numbers are needed to center it - final int WIDTH = 600; - final int HEIGHT = 600; - final int DEG_TO_PX = 10; // Magic number for how to scale pitch + // Want 60 deg to move the horizon all the way off the screen + final int DEG_TO_PX = (PY/2) / 60; // Magic number for how to scale pitch - canvas.save(0); - canvas.rotate(-roll, PX, PY); + canvas.save(); + canvas.rotate(-roll, PX / 2, PY / 2); canvas.translate(0, pitch * DEG_TO_PX); Drawable horizon = getContext().getResources().getDrawable( R.drawable.im_pfd_horizon); + // This puts the image at the center of the PFD canvas (after it was // translated) - horizon.setBounds(-(WIDTH - PX) / 2, -(HEIGHT - PY) / 2, WIDTH, HEIGHT); + double margin = 0.5; + horizon.setBounds( (int) (-margin * PX), (int) (-margin * PY), (int) ((1 + margin) * PX), (int) ((1+margin) *PY)); horizon.draw(canvas); canvas.restore(); + canvas.drawLine(0, 0, PX, 0, markerPaint); + canvas.drawLine(0, 0, 0, PY, markerPaint); + canvas.drawLine(PX, 0, PX, PY, markerPaint); + canvas.drawLine(0, PY, PX, PY, markerPaint); + + canvas.drawLine(0,PY/2,PX,PY/2,markerPaint); + canvas.drawLine(PX/2,0,PX/2,PY,markerPaint); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java index 6374c7b82..8b74fe928 100644 --- a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java @@ -28,7 +28,6 @@ import org.openpilot.androidgcs.fragments.PFD; import android.app.FragmentTransaction; import android.os.Bundle; import android.view.View; -import android.widget.AbsListView; import android.widget.LinearLayout; public class PfdActivity extends ObjectManagerActivity { @@ -44,8 +43,8 @@ public class PfdActivity extends ObjectManagerActivity { layout.setOrientation(LinearLayout.HORIZONTAL); layout.setLayoutParams(new LinearLayout.LayoutParams( - AbsListView.LayoutParams.MATCH_PARENT, - AbsListView.LayoutParams.MATCH_PARENT)); + LinearLayout.LayoutParams.WRAP_CONTENT, + LinearLayout.LayoutParams.WRAP_CONTENT)); layout.setId(0x101); { FragmentTransaction fragmentTransaction = getFragmentManager() From e65793a5d0768e78eaf019cad4a10ccffa654164 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 11:05:08 -0500 Subject: [PATCH 427/508] AndroidGCS PFD: Properly center image now so it works over multiple sizes. However, it doesn't automatically fill the screen in normal PFD view yet. Specifying the width in pfd.xml directly does fix that but is incorrect. --- .../openpilot/androidgcs/AttitudeView.java | 26 ++++++++++++------- .../org/openpilot/androidgcs/PfdActivity.java | 5 ++-- 2 files changed, 19 insertions(+), 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java index d8aecc5e1..3bf0e5227 100644 --- a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -93,25 +93,33 @@ public class AttitudeView extends View { @Override protected void onDraw(Canvas canvas) { - final int PX = getMeasuredWidth() / 2; - final int PY = getMeasuredHeight() / 2; + final int PX = getMeasuredWidth(); + final int PY = getMeasuredHeight(); - // TODO: Figure out why these magic numbers are needed to center it - final int WIDTH = 600; - final int HEIGHT = 600; - final int DEG_TO_PX = 10; // Magic number for how to scale pitch + // Want 60 deg to move the horizon all the way off the screen + final int DEG_TO_PX = (PY/2) / 60; // Magic number for how to scale pitch - canvas.save(0); - canvas.rotate(-roll, PX, PY); + canvas.save(); + canvas.rotate(-roll, PX / 2, PY / 2); canvas.translate(0, pitch * DEG_TO_PX); Drawable horizon = getContext().getResources().getDrawable( R.drawable.im_pfd_horizon); + // This puts the image at the center of the PFD canvas (after it was // translated) - horizon.setBounds(-(WIDTH - PX) / 2, -(HEIGHT - PY) / 2, WIDTH, HEIGHT); + double margin = 0.5; + horizon.setBounds( (int) (-margin * PX), (int) (-margin * PY), (int) ((1 + margin) * PX), (int) ((1+margin) *PY)); horizon.draw(canvas); canvas.restore(); + canvas.drawLine(0, 0, PX, 0, markerPaint); + canvas.drawLine(0, 0, 0, PY, markerPaint); + canvas.drawLine(PX, 0, PX, PY, markerPaint); + canvas.drawLine(0, PY, PX, PY, markerPaint); + + canvas.drawLine(0,PY/2,PX,PY/2,markerPaint); + canvas.drawLine(PX/2,0,PX/2,PY,markerPaint); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java index 6374c7b82..8b74fe928 100644 --- a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java @@ -28,7 +28,6 @@ import org.openpilot.androidgcs.fragments.PFD; import android.app.FragmentTransaction; import android.os.Bundle; import android.view.View; -import android.widget.AbsListView; import android.widget.LinearLayout; public class PfdActivity extends ObjectManagerActivity { @@ -44,8 +43,8 @@ public class PfdActivity extends ObjectManagerActivity { layout.setOrientation(LinearLayout.HORIZONTAL); layout.setLayoutParams(new LinearLayout.LayoutParams( - AbsListView.LayoutParams.MATCH_PARENT, - AbsListView.LayoutParams.MATCH_PARENT)); + LinearLayout.LayoutParams.WRAP_CONTENT, + LinearLayout.LayoutParams.WRAP_CONTENT)); layout.setId(0x101); { FragmentTransaction fragmentTransaction = getFragmentManager() From 2bf8423ed6fafa97c1c22fbad3839d70dca2e5af Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 30 Aug 2012 12:10:17 -0500 Subject: [PATCH 428/508] AndroidGCS Map: Make sure to grab the correct uavLocation and homeLocation at startup --- androidgcs/src/org/openpilot/androidgcs/UAVLocation.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java index ffb3e427c..6ee1bdbcd 100644 --- a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java +++ b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java @@ -169,9 +169,11 @@ public class UAVLocation extends MapActivity void onOPConnected() { UAVObject obj = objMngr.getObject("HomeLocation"); registerObjectUpdates(obj); + objectUpdated(obj); obj = objMngr.getObject("PositionActual"); registerObjectUpdates(obj); + objectUpdated(obj); } private GeoPoint getUavLocation() { From b34b8067721e2c100fe1693692efcd073816d19d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 30 Aug 2012 12:13:29 -0500 Subject: [PATCH 429/508] AndroidGCS Controller: Make the default value mode 2 Previously typed "Mode 2" but it wants the integer value for the default setting. This stops a crash when no configuration. --- androidgcs/res/xml/controller_preferences.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/androidgcs/res/xml/controller_preferences.xml b/androidgcs/res/xml/controller_preferences.xml index 48f263a1b..219a5146e 100644 --- a/androidgcs/res/xml/controller_preferences.xml +++ b/androidgcs/res/xml/controller_preferences.xml @@ -3,7 +3,7 @@ From 73c7190077845030054419b13e9b8dc5e18054f1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 31 Aug 2012 10:17:10 -0500 Subject: [PATCH 430/508] RM GPS: Use the CC_MainPort instead of a RV flag and enable GPS support --- flight/RevoMini/System/pios_board.c | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 1fc2eaa8a..bc0d47d90 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -450,19 +450,22 @@ void PIOS_Board_Init(void) { HwSettingsDSMxBindGet(&hwsettings_DSMxBind); /* Configure main USART port */ - uint8_t hwsettings_rv_telemetryport; - HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport); - - switch (hwsettings_rv_telemetryport){ - case HWSETTINGS_RV_TELEMETRYPORT_DISABLED: + uint8_t hwsettings_mainport; + HwSettingsCC_MainPortGet(&hwsettings_mainport); + // Disable, Telemetry, GPS, S.Bus, DSM (2,X10,X11), ComAux, ComBridge + switch (hwsettings_mainport){ + case HWSETTINGS_CC_MAINPORT_DISABLED: break; - case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY: + case HWSETTINGS_CC_MAINPORT_TELEMETRY: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); break; - case HWSETTINGS_RV_TELEMETRYPORT_COMAUX: + case HWSETTINGS_CC_MAINPORT_GPS: + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id); + break; + case HWSETTINGS_CC_MAINPORT_COMAUX: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); break; - case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE: + case HWSETTINGS_CC_MAINPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; From d333e24a433f35f8c32cabe920e9362407792dbe Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 31 Aug 2012 10:30:00 -0500 Subject: [PATCH 431/508] RM: Swap to using the CC_ flags for the flexi port too. --- flight/RevoMini/System/pios_board.c | 31 +++++----- flight/board_hw_defs/revomini/board_hw_defs.c | 58 +++++++++++++++++++ 2 files changed, 75 insertions(+), 14 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index bc0d47d90..1f01659eb 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -460,7 +460,7 @@ void PIOS_Board_Init(void) { PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); break; case HWSETTINGS_CC_MAINPORT_GPS: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id); + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); break; case HWSETTINGS_CC_MAINPORT_COMAUX: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); @@ -472,13 +472,14 @@ void PIOS_Board_Init(void) { } /* hwsettings_rv_telemetryport */ /* Configure FlexiPort */ - uint8_t hwsettings_rv_flexiport; - HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport); - - switch (hwsettings_rv_flexiport) { - case HWSETTINGS_RV_FLEXIPORT_DISABLED: + uint8_t hwsettings_flexiport; + HwSettingsCC_FlexiPortGet(&hwsettings_flexiport); + // Disable, Telemetry, GPS, S.Bus, DSM (2,X10,X11), ComAux, ComBridge + + switch (hwsettings_flexiport) { + case HWSETTINGS_CC_FLEXIPORT_DISABLED: break; - case HWSETTINGS_RV_FLEXIPORT_I2C: + case HWSETTINGS_CC_FLEXIPORT_I2C: #if defined(PIOS_INCLUDE_I2C) { if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { @@ -487,13 +488,15 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_I2C */ break; - - case HWSETTINGS_RV_FLEXIPORT_DSM2: - case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: - case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + case HWSETTINGS_CC_MAINPORT_GPS: + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); + break; + case HWSETTINGS_CC_FLEXIPORT_DSM2: + case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT: + case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT: { enum pios_dsm_proto proto; - switch (hwsettings_rv_flexiport) { + switch (hwsettings_flexiport) { case HWSETTINGS_RV_FLEXIPORT_DSM2: proto = PIOS_DSM_PROTO_DSM2; break; @@ -512,10 +515,10 @@ void PIOS_Board_Init(void) { &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); } break; - case HWSETTINGS_RV_FLEXIPORT_COMAUX: + case HWSETTINGS_CC_FLEXIPORT_COMAUX: PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); break; - case HWSETTINGS_RV_FLEXIPORT_COMBRIDGE: + case HWSETTINGS_CC_FLEXIPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; } /* hwsettings_rv_flexiport */ diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index ba8205310..ecb702c7e 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -414,6 +414,64 @@ static const struct pios_usart_cfg pios_usart_main_cfg = { }; #endif /* PIOS_INCLUDE_COM_TELEM */ +#if defined(PIOS_INCLUDE_SBUS) +/* + * S.Bus USART + */ +#include + +static const struct pios_usart_cfg pios_usart_sbus_main_cfg = { + .regs = USART1, + .init = { + .USART_BaudRate = 100000, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_Even, + .USART_StopBits = USART_StopBits_2, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, +}; + +static const struct pios_sbus_cfg pios_sbus_cfg = { + /* Inverter configuration */ + .inv = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .gpio_clk_func = RCC_APB2PeriphClockCmd, + .gpio_clk_periph = RCC_APB2Periph_GPIOC, + .gpio_inv_enable = Bit_SET, +}; + +#endif /* PIOS_INCLUDE_SBUS */ #ifdef PIOS_INCLUDE_COM_FLEXI /* From 300cee44b4d8b1bef527032594bf5270652a28f7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 31 Aug 2012 11:01:34 -0500 Subject: [PATCH 432/508] RM SBUS: There is no pull down on the inverter direction so when not SBUS must explicitly set to off. --- flight/PiOS/inc/pios_sbus_priv.h | 1 + flight/RevoMini/System/pios_board.c | 5 +++++ flight/board_hw_defs/revomini/board_hw_defs.c | 16 +++++++++------- 3 files changed, 15 insertions(+), 7 deletions(-) diff --git a/flight/PiOS/inc/pios_sbus_priv.h b/flight/PiOS/inc/pios_sbus_priv.h index 127db9a46..b9aa88515 100644 --- a/flight/PiOS/inc/pios_sbus_priv.h +++ b/flight/PiOS/inc/pios_sbus_priv.h @@ -79,6 +79,7 @@ struct pios_sbus_cfg { void (*gpio_clk_func)(uint32_t periph, FunctionalState state); uint32_t gpio_clk_periph; BitAction gpio_inv_enable; + BitAction gpio_inv_disable; }; extern const struct pios_rcvr_driver pios_sbus_rcvr_driver; diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 1f01659eb..43b7e772f 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -471,6 +471,11 @@ void PIOS_Board_Init(void) { } /* hwsettings_rv_telemetryport */ + if (hwsettings_mainport != HWSETTINGS_CC_MAINPORT_SBUS) { + GPIO_Init(pios_sbus_cfg.inv.gpio, &pios_sbus_cfg.inv.init); + GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable); + } + /* Configure FlexiPort */ uint8_t hwsettings_flexiport; HwSettingsCC_FlexiPortGet(&hwsettings_flexiport); diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index ecb702c7e..f1e722452 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -414,12 +414,11 @@ static const struct pios_usart_cfg pios_usart_main_cfg = { }; #endif /* PIOS_INCLUDE_COM_TELEM */ +#include #if defined(PIOS_INCLUDE_SBUS) /* * S.Bus USART */ -#include - static const struct pios_usart_cfg pios_usart_sbus_main_cfg = { .regs = USART1, .init = { @@ -456,22 +455,25 @@ static const struct pios_usart_cfg pios_usart_sbus_main_cfg = { }, }; +#endif /* PIOS_INCLUDE_SBUS */ + +// Need this defined regardless to be able to turn it off static const struct pios_sbus_cfg pios_sbus_cfg = { /* Inverter configuration */ .inv = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Pin = GPIO_Pin_0, .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP }, }, - .gpio_clk_func = RCC_APB2PeriphClockCmd, - .gpio_clk_periph = RCC_APB2Periph_GPIOC, .gpio_inv_enable = Bit_SET, + .gpio_inv_disable = Bit_RESET, }; -#endif /* PIOS_INCLUDE_SBUS */ #ifdef PIOS_INCLUDE_COM_FLEXI /* From a33f415866139bac5bbd14a96fd322201c461bb8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 31 Aug 2012 11:08:43 -0500 Subject: [PATCH 433/508] RM DSM: Get DSM working on the mainport Because of the inverter this does not support binding on this port. --- flight/RevoMini/System/pios_board.c | 34 ++++++++-- flight/board_hw_defs/revomini/board_hw_defs.c | 62 +++++++++++++++++++ 2 files changed, 92 insertions(+), 4 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 43b7e772f..3c0bf7863 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -462,7 +462,33 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_MAINPORT_GPS: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); break; - case HWSETTINGS_CC_MAINPORT_COMAUX: + case HWSETTINGS_CC_MAINPORT_SBUS: + // TODO + break; + case HWSETTINGS_CC_MAINPORT_DSM2: + case HWSETTINGS_CC_MAINPORT_DSMX10BIT: + case HWSETTINGS_CC_MAINPORT_DSMX11BIT: + { + enum pios_dsm_proto proto; + switch (hwsettings_mainport) { + case HWSETTINGS_CC_MAINPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_CC_MAINPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_CC_MAINPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here + PIOS_Board_configure_dsm(&pios_usart_dsm_main_cfg, &pios_dsm_main_cfg, + &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); + } + break; case HWSETTINGS_CC_MAINPORT_COMAUX: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); break; case HWSETTINGS_CC_MAINPORT_COMBRIDGE: @@ -502,13 +528,13 @@ void PIOS_Board_Init(void) { { enum pios_dsm_proto proto; switch (hwsettings_flexiport) { - case HWSETTINGS_RV_FLEXIPORT_DSM2: + case HWSETTINGS_CC_FLEXIPORT_DSM2: proto = PIOS_DSM_PROTO_DSM2; break; - case HWSETTINGS_RV_FLEXIPORT_DSMX10BIT: + case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT: proto = PIOS_DSM_PROTO_DSMX10BIT; break; - case HWSETTINGS_RV_FLEXIPORT_DSMX11BIT: + case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT: proto = PIOS_DSM_PROTO_DSMX11BIT; break; default: diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index f1e722452..af1791291 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -414,6 +414,68 @@ static const struct pios_usart_cfg pios_usart_main_cfg = { }; #endif /* PIOS_INCLUDE_COM_TELEM */ +#ifdef PIOS_INCLUDE_DSM + +#include "pios_dsm_priv.h" +static const struct pios_usart_cfg pios_usart_dsm_main_cfg = { + .regs = USART1, + .remap = GPIO_AF_USART1, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +// Because of the inverter on the main port this will not +// work. Notice the mode is set to IN to maintain API +// compatibility but protect the pins +static const struct pios_dsm_cfg pios_dsm_main_cfg = { + .bind = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + }, +}; + +#endif /* PIOS_INCLUDE_DSM */ + #include #if defined(PIOS_INCLUDE_SBUS) /* From f3327e3993bd5bc839428beadc9d48616bfaac60 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 10:58:06 -0500 Subject: [PATCH 434/508] RM: Enabled optional modules and got the battery module working again. Changed the hardcoded (ick) battery lines for RM. Also removed the reference to PIOS_ADC_GetPin(4) as that pin is no longer available. Finally changed the default FlightBatterySettings to work out of the box for the standard recommended sensors. --- flight/Modules/Battery/battery.c | 44 ------------------- flight/PiOS/Boards/STM32F4xx_RevoMini.h | 12 ++--- flight/RevoMini/Makefile | 6 +-- flight/RevoMini/System/inc/pios_config.h | 2 +- .../flightbatterysettings.xml | 4 +- 5 files changed, 12 insertions(+), 56 deletions(-) diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index 1479d7699..521556fb1 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -55,9 +55,6 @@ // Configuration // #define SAMPLE_PERIOD_MS 500 -#define BATTERY_BOARD_VOLTAGE_WARNING 4.5 -#define BATTERY_BOARD_VOLTAGE_CRITICAL 3.5 -#define BATTERY_BOARD_VOLTAGE_ERROR 1.0 // Private types // Private variables @@ -104,9 +101,6 @@ MODULE_INITCALL(BatteryInitialize, 0) static void onTimer(UAVObjEvent* ev) { static FlightBatteryStateData flightBatteryData; - static bool BoardPowerWarning= false; - // prevent that the initial ramp up of the power supply rail is identified as a power failure. - static bool BoardPowerOk = false; FlightBatterySettingsData batterySettings; FlightBatterySettingsGet(&batterySettings); @@ -114,17 +108,11 @@ static void onTimer(UAVObjEvent* ev) static float dT = SAMPLE_PERIOD_MS / 1000.0; float energyRemaining; - if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BOARDVOLTAGE) ) - flightBatteryData.BoardSupplyVoltage=((float)PIOS_ADC_PinGet(4)) * PIOS_ADC_VOLTAGE_SCALE * 6.1; - else - flightBatteryData.BoardSupplyVoltage = -1; - //calculate the battery parameters if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYVOLTAGE) ) flightBatteryData.Voltage = ((float)PIOS_ADC_PinGet(0)) * PIOS_ADC_VOLTAGE_SCALE * batterySettings.SensorCalibrations[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONS_VOLTAGEFACTOR]; //in Volts else flightBatteryData.Voltage = -1; - if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BATTERYCURRENT)) { @@ -188,38 +176,6 @@ static void onTimer(UAVObjEvent* ev) } } - if(HAS_SENSOR(FLIGHTBATTERYSETTINGS_SENSORTYPE_BOARDVOLTAGE) ) - { - // power ia disconnected from the board (it is powered by usb) - if(flightBatteryData.BoardSupplyVoltage!= -1 && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_ERROR) - { - AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_ERROR); - BoardPowerWarning=false; - BoardPowerOk = false; - } - else - { - if(BoardPowerOk && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_CRITICAL) - { - AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_CRITICAL); - BoardPowerWarning=true; - } - else if (BoardPowerOk && flightBatteryData.BoardSupplyVoltage < BATTERY_BOARD_VOLTAGE_WARNING) - { - AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); - BoardPowerWarning=true; - } - else - { - // if there was any previous warning/critical condition, notify the problem leaving the warning - if(BoardPowerWarning) - AlarmsSet(SYSTEMALARMS_ALARM_POWER, SYSTEMALARMS_ALARM_WARNING); - else - AlarmsClear(SYSTEMALARMS_ALARM_POWER); - BoardPowerOk |= flightBatteryData.BoardSupplyVoltage > BATTERY_BOARD_VOLTAGE_WARNING; - } - } - } FlightBatteryStateSet(&flightBatteryData); } diff --git a/flight/PiOS/Boards/STM32F4xx_RevoMini.h b/flight/PiOS/Boards/STM32F4xx_RevoMini.h index dfec89387..819d6a32d 100644 --- a/flight/PiOS/Boards/STM32F4xx_RevoMini.h +++ b/flight/PiOS/Boards/STM32F4xx_RevoMini.h @@ -259,12 +259,12 @@ extern uint32_t pios_packet_handler; // PIOS_ADC_PinGet(4) = VREF // PIOS_ADC_PinGet(5) = Temperature sensor //------------------------- -#define PIOS_DMA_PIN_CONFIG \ -{ \ - {GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ - {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ - {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ - {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ +#define PIOS_DMA_PIN_CONFIG \ +{ \ + {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ + {GPIOC, GPIO_Pin_2, ADC_Channel_12}, \ + {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ + {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ {GPIOC, GPIO_Pin_2, ADC_Channel_12} \ } diff --git a/flight/RevoMini/Makefile b/flight/RevoMini/Makefile index 06dd2228f..a5012e0f3 100644 --- a/flight/RevoMini/Makefile +++ b/flight/RevoMini/Makefile @@ -52,12 +52,12 @@ FLASH_TOOL = OPENOCD MODULES = Sensors MODULES += Attitude/revolution MODULES += ManualControl Stabilization Actuator -#MODULES += Battery +MODULES += Battery MODULES += Altitude/revolution MODULES += GPS FirmwareIAP #MODULES += Airspeed/revolution -#MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner -#MODULES += CameraStab +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +MODULES += CameraStab MODULES += Radio MODULES += Telemetry PYMODULES = diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 9b1bbb554..75e0dbc96 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -39,7 +39,7 @@ #define PIOS_INCLUDE_BL_HELPER /* Enable/Disable PiOS Modules */ -//#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_ADC #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_I2C #define PIOS_INCLUDE_IRQ diff --git a/shared/uavobjectdefinition/flightbatterysettings.xml b/shared/uavobjectdefinition/flightbatterysettings.xml index 874fada83..ed0b1f19a 100644 --- a/shared/uavobjectdefinition/flightbatterysettings.xml +++ b/shared/uavobjectdefinition/flightbatterysettings.xml @@ -8,8 +8,8 @@ - - + + From 0d3b0d4e5b875b3c6cfded9eeca897b13cb29794 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 11:11:28 -0500 Subject: [PATCH 435/508] Fixup: Disable binding on mainport for DSM --- flight/RevoMini/System/pios_board.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 3c0bf7863..89ff48e58 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -484,6 +484,10 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); break; } + + // Force binding to zero on the main port + hwsettings_DSMxBind = 0; + //TODO: Define the various Channelgroup for Revo dsm inputs and handle here PIOS_Board_configure_dsm(&pios_usart_dsm_main_cfg, &pios_dsm_main_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hwsettings_DSMxBind); From 878def305f001bfd414d1c2023f746332c8a036a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 11:11:44 -0500 Subject: [PATCH 436/508] RM: Make radio an optional module --- flight/RevoMini/System/inc/pios_config.h | 1 - 1 file changed, 1 deletion(-) diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/RevoMini/System/inc/pios_config.h index 75e0dbc96..7406895b2 100644 --- a/flight/RevoMini/System/inc/pios_config.h +++ b/flight/RevoMini/System/inc/pios_config.h @@ -59,7 +59,6 @@ /* Variables related to the RFM22B functionality */ #define PIOS_INCLUDE_RFM22B #define RFM22_EXT_INT_USE -#define RADIO_BUILTIN /* Select the sensors to include */ #define PIOS_INCLUDE_HMC5883 From 2c003d8b0b7e088dfb8c6603284677bc2e8df432 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 16:49:15 -0500 Subject: [PATCH 437/508] PathCompiler: Link up the path compiler to the map again. Got broken in the merge. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 94 +++++-------------- .../src/plugins/opmap/opmapgadgetwidget.h | 5 +- 2 files changed, 28 insertions(+), 71 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 01d006cf7..4405d2b2e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -267,6 +267,11 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_statusUpdateTimer->start(); m_map->setFocus(); + + // Create the path compiler and connect the signals to it + pathCompiler = new PathCompiler(this); + connect(pathCompiler, SIGNAL(visualizationChanged(QList)), + this, SLOT(doVisualizationChanged(QList))); } // destructor @@ -476,13 +481,10 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) contextMenu.addSeparator()->setText(tr("Waypoints")); - contextMenu.addAction(wayPointEditorAct); contextMenu.addAction(addWayPointAct); if (m_mouse_waypoint) { // we have a waypoint under the mouse - contextMenu.addAction(editWayPointAct); - lockWayPointAct->setChecked(waypoint_locked); contextMenu.addAction(lockWayPointAct); @@ -1295,11 +1297,6 @@ void OPMapGadgetWidget::createActions() followUAVheadingAct->setChecked(false); connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); - addWayPointAct = new QAction(tr("&Add waypoint"), this); - addWayPointAct->setShortcut(tr("Ctrl+A")); - addWayPointAct->setStatusTip(tr("Add waypoint")); - connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); - overlayOpacityActGroup = new QActionGroup(this); connect(overlayOpacityActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onOverlayOpacityActGroup_triggered(QAction *))); overlayOpacityAct.clear(); @@ -1443,71 +1440,30 @@ void OPMapGadgetWidget::createActions() uavTrailDistanceAct.append(uavTrailDistance_act); } -// // GPS trail -// // TODO: Delete this action ? -// showGPSAct = new QAction(tr("Show GPS"), this); -// showGPSAct->setStatusTip(tr("Show/Hide the GPS")); -// showGPSAct->setCheckable(true); -// showGPSAct->setChecked(false); -// connect(showGPSAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPSAct_toggled(bool))); + //GPS trail + showGPSAct = new QAction(tr("Show GPS"), this); + showGPSAct->setStatusTip(tr("Show/Hide the GPS")); + showGPSAct->setCheckable(true); + showGPSAct->setChecked(false); + connect(showGPSAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPSAct_toggled(bool))); -// gpsTrailTypeActGroup = new QActionGroup(this); -// connect(gpsTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTypeActGroup_triggered(QAction *))); -// gpsTrailTypeAct.clear(); -// QStringList gps_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); -// for (int i = 0; i < gps_trail_type_list.count(); i++) -// { -// mapcontrol::UAVTrailType::Types gps_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(gps_trail_type_list[i]); -// QAction *gpsTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(gps_trail_type), gpsTrailTypeActGroup); -// gpsTrailType_act->setCheckable(true); -// gpsTrailType_act->setChecked(gps_trail_type == m_map->GPS->GetTrailType()); -// gpsTrailType_act->setData(i); -// gpsTrailTypeAct.append(gpsTrailType_act); -// } + /** Actions for way points **/ + addWayPointAct = new QAction(tr("&Add waypoint"), this); + addWayPointAct->setShortcut(tr("Ctrl+A")); + addWayPointAct->setStatusTip(tr("Add waypoint")); + connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); -// showGPStrailAct = new QAction(tr("Show Trail dots"), this); -// showGPStrailAct->setStatusTip(tr("Show/Hide the Trail dots")); -// showGPStrailAct->setCheckable(true); -// showGPStrailAct->setChecked(false); -// connect(showGPStrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailAct_toggled(bool))); + clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); + clearWayPointsAct->setStatusTip(tr("Clear all the waypoints")); + connect(clearWayPointsAct, SIGNAL(triggered()),this, SLOT(onClearWayPointsAct_triggered())); -// showGPStrailLineAct = new QAction(tr("Show Trail lines"), this); -// showGPStrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); -// showGPStrailLineAct->setCheckable(true); -// showGPStrailLineAct->setChecked(true); -// connect(showGPStrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailLineAct_toggled(bool))); + deleteWayPointAct = new QAction(tr("&Del waypoint"), this); + deleteWayPointAct->setStatusTip(tr("Delete this waypoint")); + connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered())); -// clearGPStrailAct = new QAction(tr("Clear GPS trail"), this); -// clearGPStrailAct->setStatusTip(tr("Clear the GPS trail")); -// connect(clearGPStrailAct, SIGNAL(triggered()), this, SLOT(onClearGPStrailAct_triggered())); - -// gpsTrailTimeActGroup = new QActionGroup(this); -// connect(gpsTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTimeActGroup_triggered(QAction *))); -// gpsTrailTimeAct.clear(); -// list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); -// for (int i = 0; i < list_size; i++) -// { -// int gps_trail_time = uav_trail_time_list[i]; -// QAction *gpsTrailTime_act = new QAction(QString::number(gps_trail_time) + " sec", gpsTrailTimeActGroup); -// gpsTrailTime_act->setCheckable(true); -// gpsTrailTime_act->setChecked(gps_trail_time == m_map->GPS->TrailTime()); -// gpsTrailTime_act->setData(gps_trail_time); -// gpsTrailTimeAct.append(gpsTrailTime_act); -// } - -// gpsTrailDistanceActGroup = new QActionGroup(this); -// connect(gpsTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailDistanceActGroup_triggered(QAction *))); -// gpsTrailDistanceAct.clear(); -// list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); -// for (int i = 0; i < list_size; i++) -// { -// int gps_trail_distance = uav_trail_distance_list[i]; -// QAction *gpsTrailDistance_act = new QAction(QString::number(gps_trail_distance) + " meters", gpsTrailDistanceActGroup); -// gpsTrailDistance_act->setCheckable(true); -// gpsTrailDistance_act->setChecked(gps_trail_distance == m_map->GPS->TrailDistance()); -// gpsTrailDistance_act->setData(gps_trail_distance); -// gpsTrailDistanceAct.append(gpsTrailDistance_act); -// } + lockWayPointAct = new QAction(tr("&Lock waypoints"), this); + lockWayPointAct->setStatusTip(tr("Lock a waypoint location")); + connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered())); } void OPMapGadgetWidget::onReloadAct_triggered() diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 8c9870590..f2413a418 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -275,13 +275,14 @@ private: QAction *goUAVAct; QAction *followUAVpositionAct; QAction *followUAVheadingAct; - QAction *wayPointEditorAct; + QAction *homeMagicWaypointAct; + + // Waypoint actions QAction *addWayPointAct; QAction *editWayPointAct; QAction *lockWayPointAct; QAction *deleteWayPointAct; QAction *clearWayPointsAct; - QAction *homeMagicWaypointAct; QAction *showSafeAreaAct; QAction *changeDefaultLocalAndZoom; From d9ec6454c290347ad04bf92c8ce993a11bef39ac Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 19:13:11 -0500 Subject: [PATCH 438/508] PipX: Since we are calling the PipX ISR from user space looks ensure the frequency stays correct. Previously it was polling too fast and the PipXStatus was incorrect as a result. Now make sure the stats loop only runs at 500 ms. --- flight/Modules/Radio/radio.c | 10 +++- flight/PiOS/Common/pios_usb_util.c | 84 +++++++++++++++--------------- flight/PiOS/inc/pios_usb_defs.h | 1 + flight/PiOS/inc/pios_usb_util.h | 76 +++++++++++++-------------- 4 files changed, 89 insertions(+), 82 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 6055e38d8..3ca5da22a 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -443,9 +443,11 @@ static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) */ static void radioStatusTask(void *parameters) { + static portTickType lastSysTime; PHStatusPacket status_packet; - while (1) { + lastSysTime = xTaskGetTickCount(); + PipXStatusData pipxStatus; uint32_t pairID; @@ -524,8 +526,12 @@ static void radioStatusTask(void *parameters) } } - for(int i = 0; i < 20; i++) + portTickType timeSinceUpdate; + do { PIOS_RFM22_processPendingISR(5); + timeSinceUpdate = xTaskGetTickCount() - lastSysTime; + } + while(timeSinceUpdate < STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); } } diff --git a/flight/PiOS/Common/pios_usb_util.c b/flight/PiOS/Common/pios_usb_util.c index 6949bd004..4bbf98d23 100644 --- a/flight/PiOS/Common/pios_usb_util.c +++ b/flight/PiOS/Common/pios_usb_util.c @@ -1,42 +1,42 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB_UTIL USB utility functions - * @brief USB utility functions - * @{ - * - * @file pios_usb_util.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief USB utility functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios_usb_util.h" - -uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen) -{ - for (uint8_t i = 0; i < srclen; i++) { - *dst = *src; - dst += 2; - src += 1; - } - - return dst; -} +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_UTIL USB utility functions + * @brief USB utility functions + * @{ + * + * @file pios_usb_util.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USB utility functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_util.h" + +uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen) +{ + for (uint8_t i = 0; i < srclen; i++) { + *dst = *src; + dst += 2; + src += 1; + } + + return dst; +} diff --git a/flight/PiOS/inc/pios_usb_defs.h b/flight/PiOS/inc/pios_usb_defs.h index ea54306a7..a26ff4425 100644 --- a/flight/PiOS/inc/pios_usb_defs.h +++ b/flight/PiOS/inc/pios_usb_defs.h @@ -364,6 +364,7 @@ enum usb_op_board_ids { USB_OP_BOARD_ID_PIPXTREME = 3, USB_OP_BOARD_ID_COPTERCONTROL = 4, USB_OP_BOARD_ID_REVOLUTION = 5, + USB_OP_BOARD_ID_OSD = 6, } __attribute__((packed)); enum usb_op_board_modes { diff --git a/flight/PiOS/inc/pios_usb_util.h b/flight/PiOS/inc/pios_usb_util.h index 114cd9a70..111b49239 100644 --- a/flight/PiOS/inc/pios_usb_util.h +++ b/flight/PiOS/inc/pios_usb_util.h @@ -1,38 +1,38 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB_UTIL USB utility functions - * @brief USB utility functions - * @{ - * - * @file pios_usb_util.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief USB utility functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_USB_UTIL_H -#define PIOS_USB_UTIL_H - -#include /* uint8_t */ - -uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen); - -#endif /* PIOS_USB_UTIL_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_UTIL USB utility functions + * @brief USB utility functions + * @{ + * + * @file pios_usb_util.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USB utility functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_UTIL_H +#define PIOS_USB_UTIL_H + +#include /* uint8_t */ + +uint8_t * PIOS_USB_UTIL_AsciiToUtf8(uint8_t * dst, uint8_t * src, uint16_t srclen); + +#endif /* PIOS_USB_UTIL_H */ From fcbf01fa7464c73b9555374ff403a7ef15233892 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Mon, 27 Aug 2012 19:10:54 -0700 Subject: [PATCH 439/508] RFM22b: Added SPI initialization back into PipX pios_board.c. Signed-off-by: James Cotton --- flight/PipXtreme/System/pios_board.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/flight/PipXtreme/System/pios_board.c b/flight/PipXtreme/System/pios_board.c index 84aa36d50..863fbb961 100644 --- a/flight/PipXtreme/System/pios_board.c +++ b/flight/PipXtreme/System/pios_board.c @@ -68,6 +68,11 @@ void PIOS_Board_Init(void) { /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); + + /* Set up the SPI interface to the rfm22b */ + if (PIOS_SPI_Init(&pios_spi_rfm22b_id, &pios_spi_rfm22b_cfg)) { + PIOS_DEBUG_Assert(0); + } #ifdef PIOS_INCLUDE_WDG /* Initialize watchdog as early as possible to catch faults during init */ From 27fedee3d3b94b193f128b49fb95887e185b0596 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 28 Aug 2012 19:58:21 -0700 Subject: [PATCH 440/508] Just return an initialization failure in the radio module when the RFM22B fails to initialize rather than asserting. Signed-off-by: James Cotton --- flight/Modules/Radio/radio.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 3ca5da22a..e05478671 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -235,7 +235,7 @@ static int32_t RadioInitialize(void) /* Initalize the RFM22B radio COM device. */ { if (PIOS_RFM22B_Init(&pios_rfm22b_id, &pios_rfm22b_cfg)) { - PIOS_Assert(0); + return -1; } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); From 997319ae8035169215e7c30f3e8f81ba575150e5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 21:07:38 -0500 Subject: [PATCH 441/508] RFM22b: Begin doing blocks of transfers when possible between semaphore claims The abstraction should probably be improved but ideally we start using the DMA SPI transfers for PipX and grabbing/releasing the semaphore less frequently (e.g. not for each 1-2 bytes). --- flight/PiOS/Common/pios_rfm22b.c | 29 +++++++++++++++++++++-------- 1 file changed, 21 insertions(+), 8 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 8d35bf917..ebbe413cb 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1540,15 +1540,28 @@ static void rfm22_processInt(void) // Reset the supervisor timer. rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; - // read interrupt status registers - clears the interrupt line - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); + // 1. Read the interrupt statuses with burst read + rfm22_claimBus(); // Set RC and the semaphore + uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF}; + uint8_t read_buf[3]; + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, sizeof(write_buf), NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + int_status1 = read_buf[1]; + int_status2 = read_buf[2]; + + // Device status + write_buf[0] = RFM22_device_status & 0x7f; + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, 2, NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + device_status = read_buf[1]; - // read device status register - device_status = rfm22_read(RFM22_device_status); - - // read ezmac status register - ezmac_status = rfm22_read(RFM22_ezmac_status); + // EzMAC status + write_buf[0] = RFM22_ezmac_status & 0x7f; + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, 2, NULL); + ezmac_status = read_buf[1]; + rfm22_releaseBus(); // Read the RSSI if we're in RX mode if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && From 588297806c3789894d1a03aeae4ad38d176f32d9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 21:24:42 -0500 Subject: [PATCH 442/508] RFM22b: Use SPI block transfers for filling the RFM22b FIFO Also removed the disable irq line since that was introducing flight glitches. --- flight/PiOS/Common/pios_rfm22b.c | 29 +++++++++++++++-------------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index ebbe413cb..43f618755 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1151,9 +1151,6 @@ uint8_t rfm22_txStart() exec_using_spi = true; - // Disable interrrupts. - PIOS_IRQ_Disable(); - // Initialize the supervisor timer. rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; @@ -1199,10 +1196,14 @@ uint8_t rfm22_txStart() rfm22_write(RFM22_transmit_packet_length, tx_data_wr); // add some data - rfm22_startBurstWrite(RFM22_fifo_access); - for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < FIFO_SIZE); ++tx_data_rd, ++i) - rfm22_burstWrite(tx_buffer[tx_data_rd]); - rfm22_endBurstWrite(); + rfm22_claimBus(); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); + int bytes_to_write = (tx_data_wr - tx_data_rd); + bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write; + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + tx_data_rd += bytes_to_write; + rfm22_releaseBus(); + // ******************* @@ -1217,9 +1218,6 @@ uint8_t rfm22_txStart() // enable the transmitter rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); - // Re-ensable interrrupts. - PIOS_IRQ_Enable(); - TX_LED_ON; exec_using_spi = false; @@ -1506,10 +1504,13 @@ void rfm22_processTxInt(void) { // top-up the rf chips TX FIFO buffer uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; - rfm22_startBurstWrite(RFM22_fifo_access); - for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < max_bytes); ++i, ++tx_data_rd) - rfm22_burstWrite(tx_buffer[tx_data_rd]); - rfm22_endBurstWrite(); + rfm22_claimBus(); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); + int bytes_to_write = (tx_data_wr - tx_data_rd); + bytes_to_write = (bytes_to_write > max_bytes) ? max_bytes: bytes_to_write; + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + tx_data_rd += bytes_to_write; + rfm22_releaseBus(); } // Packet has been sent From 311bbcb53972921642aaf63d30574202ec27d563 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 2 Sep 2012 13:31:09 -0500 Subject: [PATCH 443/508] RFM22b: Block transfers for more large SPI transfers Preallocated buffers with various preambles etc. Used SPI_TransferBlock for anything over a few bytes instead of burstWrite. Also make more of the communications wrappered in a large semaphore grab using a new rfm22_write_noclaim() Still needs work - probably because most of the methods to repeated calls they should all use the noclaim, or more specifically that function becomes rfm22_write/read. --- flight/PiOS/Common/pios_rfm22b.c | 136 +++++++++++++++++-------------- 1 file changed, 77 insertions(+), 59 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 43f618755..8280a8126 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -74,8 +74,6 @@ #define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms) -//#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles) -//#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles) #define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles) #define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles) @@ -178,6 +176,23 @@ struct pios_rfm22b_dev { uint32_t random32 = 0x459ab8d8; +// Must ensure these prefilled arrays match the define sizes +static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = + {PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, + PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE}; // 64 bytes +static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1)/2 + 2] = {PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2}; + /* Local function forwared declarations */ static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); static void rfm22_processInt(void); @@ -688,6 +703,18 @@ void rfm22_write(uint8_t addr, uint8_t data) rfm22_releaseBus(); } +/** + * Write a byte to a register without claiming the bus. Also + * toggle the NSS line + */ +static void rfm22_write_noclaim(uint8_t addr, uint8_t data) +{ + uint8_t buf[2] = {addr | 0x80, data}; + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, buf, NULL, 2, NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); +} + void rfm22_startBurstRead(uint8_t addr) { // wait 1us .. so we don't toggle the CS line to quickly @@ -703,6 +730,7 @@ void rfm22_endBurstRead(void) rfm22_releaseBus(); } +//! Read a byte from tan address and claim/release the semaphore uint8_t rfm22_read(uint8_t addr) { uint8_t rdata; @@ -720,6 +748,20 @@ uint8_t rfm22_read(uint8_t addr) return rdata; } +/** + * Read a byte from a register without claiming the bus. Also + * toggle the NSS line + */ +static uint8_t rfm22_read_noclaim(uint8_t addr) +{ + uint8_t buf[2] = {addr | 0x80, 0xFF}; + uint8_t read[2]; + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, buf, read, 2, NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + return read[1]; +} + // ************************************ // external interrupt @@ -1123,23 +1165,6 @@ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) // ************************************ -uint16_t rfm22_addHeader() -{ - uint16_t i = 0; - - for (uint16_t j = (TX_PREAMBLE_NIBBLES + 1) / 2; j > 0; j--) - { - rfm22_burstWrite(PREAMBLE_BYTE); - i++; - } - rfm22_burstWrite(SYNC_BYTE_1); i++; - rfm22_burstWrite(SYNC_BYTE_2); i++; - - return i; -} - -// ************************************ - uint8_t rfm22_txStart() { if((tx_pre_buffer_size == 0) || (exec_using_spi == true)) @@ -1230,39 +1255,40 @@ static void rfm22_setTxMode(uint8_t mode) if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE) return; // invalid mode - exec_using_spi = true; + rfm22_claimBus(); - // disable interrupts - rfm22_write(RFM22_interrupt_enable1, 0x00); - rfm22_write(RFM22_interrupt_enable2, 0x00); + // Disaable interrupts (IE1, IE2 = 0) + uint8_t out_buf[3] = {RFM22_interrupt_enable1 | 0x80, 0x00, 0x00}; + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, out_buf, NULL, sizeof(out_buf), NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); // TUNE mode - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + rfm22_write_noclaim(RFM22_op_and_func_ctrl1,RFM22_opfc1_pllon); RX_LED_OFF; - // set the tx power - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | + // Set the tx power + rfm22_write_noclaim(RFM22_tx_power,RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + uint8_t fd_bit = rfm22_read_noclaim(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; if (mode == TX_CARRIER_MODE) // blank carrier mode - for testing - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | + rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier else if (mode == TX_PN_MODE) // psuedo random data carrier mode - for testing - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | + rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier else // data transmission // FIFO mode, GFSK modulation - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); // clear FIFOs - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + rfm22_write_noclaim(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write_noclaim(RFM22_op_and_func_ctrl2, 0x00); // add some data to the chips TX FIFO before enabling the transmitter { @@ -1271,30 +1297,26 @@ static void rfm22_setTxMode(uint8_t mode) if (mode == TX_DATA_MODE) // set the total number of data bytes we are going to transmit - rfm22_write(RFM22_transmit_packet_length, wr); + rfm22_write_noclaim(RFM22_transmit_packet_length, wr); - uint16_t max_bytes = FIFO_SIZE - 1; uint16_t i = 0; - rfm22_startBurstWrite(RFM22_fifo_access); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | RFM22_fifo_access); // Initiate burst write if (mode == TX_STREAM_MODE) { - if (rd >= wr) { - // no data to send - yet .. just send preamble pattern - while (true) { - rfm22_burstWrite(PREAMBLE_BYTE); - if (++i >= max_bytes) break; - } - } else // add the RF heaader - i += rfm22_addHeader(); + if (rd >= wr) + i += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, FULL_PREAMBLE, NULL, sizeof(FULL_PREAMBLE), NULL); + else // add the RF heaader + i += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, HEADER, NULL, sizeof(HEADER), NULL); } - // add some data - for (uint16_t j = wr - rd; j > 0; j--) { - rfm22_burstWrite(tx_buffer[rd++]); - if (++i >= max_bytes) - break; - } + // Send data if there is any and there is space in the buffer available + // Bytes available to send minus how many we have sent + int32_t bytes_to_send = wr - rd; + bytes_to_send = ((bytes_to_send + i)> FIFO_SIZE) ? (FIFO_SIZE - i) : bytes_to_send; + if (bytes_to_send > 0) + rd += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[rd], NULL, bytes_to_send, NULL); - rfm22_endBurstWrite(); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); tx_data_rd = rd; } @@ -1306,22 +1328,18 @@ static void rfm22_setTxMode(uint8_t mode) // enable TX interrupts // rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr); - rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); + rfm22_write_noclaim(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); // read interrupt status - clear interrupts - rfm22_read(RFM22_interrupt_status1); - rfm22_read(RFM22_interrupt_status2); + rfm22_read_noclaim(RFM22_interrupt_status1); + rfm22_read_noclaim(RFM22_interrupt_status2); // enable the transmitter // rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon); - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + rfm22_releaseBus(); TX_LED_ON; - - // ******************* - - exec_using_spi = false; - } // ************************************ From 61ff335eaa1e79f897c1c7417799456545dcaca6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 2 Sep 2012 22:15:20 -0500 Subject: [PATCH 444/508] RFM22: No need to poll the ISR from two tasks in radio.c --- flight/Modules/Radio/radio.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index e05478671..e84f34be3 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -315,8 +315,6 @@ static void radioReceiveTask(void *parameters) PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); #endif /* PIOS_INCLUDE_WDG */ - PIOS_RFM22_processPendingISR(5); - // Get a RX packet from the packet handler if required. if (p == NULL) p = PHGetRXPacket(pios_packet_handler); From dce4f36328e90854891cfe5fd1573808036c8898 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 2 Sep 2012 13:40:13 -0500 Subject: [PATCH 445/508] RFM22b: More block claims for rfm22_txStart Warning: This patch makes the modem work more poorly --- flight/PiOS/Common/pios_rfm22b.c | 59 +++++++++++++++----------------- 1 file changed, 27 insertions(+), 32 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 8280a8126..487fbb2ca 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1175,17 +1175,16 @@ uint8_t rfm22_txStart() } exec_using_spi = true; + rfm22_claimBus(); // Initialize the supervisor timer. rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; // disable interrupts - rfm22_write(RFM22_interrupt_enable1, 0x00); - rfm22_write(RFM22_interrupt_enable2, 0x00); - + rfm22_write_noclaim(RFM22_interrupt_enable1, 0x00); + rfm22_write_noclaim(RFM22_interrupt_enable2, 0x00); // TUNE mode - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); - + rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // Queue the data up for sending memcpy(tx_buffer, tx_pre_buffer, tx_pre_buffer_size); tx_data_rd = 0; @@ -1196,41 +1195,35 @@ uint8_t rfm22_txStart() // Set the destination address in the transmit header. // The destination address is the first 4 bytes of the message. - rfm22_write(RFM22_transmit_header0, tx_buffer[0]); - rfm22_write(RFM22_transmit_header1, tx_buffer[1]); - rfm22_write(RFM22_transmit_header2, tx_buffer[2]); - rfm22_write(RFM22_transmit_header3, tx_buffer[3]); + // TODO: Block transfer + rfm22_write_noclaim(RFM22_transmit_header0, tx_buffer[0]); + rfm22_write_noclaim(RFM22_transmit_header1, tx_buffer[1]); + rfm22_write_noclaim(RFM22_transmit_header2, tx_buffer[2]); + rfm22_write_noclaim(RFM22_transmit_header3, tx_buffer[3]); // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + uint8_t fd_bit = rfm22_read_noclaim(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); - // set the tx power - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | + + // Set the tx power + // TODO: Only set the power when it changes and remove this + rfm22_write_noclaim(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // clear FIFOs - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + rfm22_write_noclaim(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write_noclaim(RFM22_op_and_func_ctrl2, 0x00); - // ******************* // add some data to the chips TX FIFO before enabling the transmitter - - // set the total number of data bytes we are going to transmit - rfm22_write(RFM22_transmit_packet_length, tx_data_wr); - - // add some data - rfm22_claimBus(); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); int bytes_to_write = (tx_data_wr - tx_data_rd); bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write; - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); - tx_data_rd += bytes_to_write; - rfm22_releaseBus(); - - - // ******************* + rfm22_write_noclaim(RFM22_transmit_packet_length, bytes_to_write); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); + tx_data_rd +=PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); // reset the timer rfm22_int_timer = 0; @@ -1238,14 +1231,15 @@ uint8_t rfm22_txStart() rf_mode = TX_DATA_MODE; // enable TX interrupts - rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); - + rfm22_write_noclaim(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); // enable the transmitter - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); TX_LED_ON; + rfm22_releaseBus(); exec_using_spi = false; + return 1; } @@ -1339,6 +1333,7 @@ static void rfm22_setTxMode(uint8_t mode) rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); rfm22_releaseBus(); + TX_LED_ON; } From 0b947b243d22477b2a7fcdcb6d3b7245ee1ee4ea Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 2 Sep 2012 22:16:59 -0500 Subject: [PATCH 446/508] Revert "RFM22b: More block claims for rfm22_txStart" This reverts commit fa4ca426abf5671fc7d0b7206f85f14bcbf92c3d. --- flight/PiOS/Common/pios_rfm22b.c | 59 +++++++++++++++++--------------- 1 file changed, 32 insertions(+), 27 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 487fbb2ca..8280a8126 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1175,16 +1175,17 @@ uint8_t rfm22_txStart() } exec_using_spi = true; - rfm22_claimBus(); // Initialize the supervisor timer. rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; // disable interrupts - rfm22_write_noclaim(RFM22_interrupt_enable1, 0x00); - rfm22_write_noclaim(RFM22_interrupt_enable2, 0x00); + rfm22_write(RFM22_interrupt_enable1, 0x00); + rfm22_write(RFM22_interrupt_enable2, 0x00); + // TUNE mode - rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); + // Queue the data up for sending memcpy(tx_buffer, tx_pre_buffer, tx_pre_buffer_size); tx_data_rd = 0; @@ -1195,35 +1196,41 @@ uint8_t rfm22_txStart() // Set the destination address in the transmit header. // The destination address is the first 4 bytes of the message. - // TODO: Block transfer - rfm22_write_noclaim(RFM22_transmit_header0, tx_buffer[0]); - rfm22_write_noclaim(RFM22_transmit_header1, tx_buffer[1]); - rfm22_write_noclaim(RFM22_transmit_header2, tx_buffer[2]); - rfm22_write_noclaim(RFM22_transmit_header3, tx_buffer[3]); + rfm22_write(RFM22_transmit_header0, tx_buffer[0]); + rfm22_write(RFM22_transmit_header1, tx_buffer[1]); + rfm22_write(RFM22_transmit_header2, tx_buffer[2]); + rfm22_write(RFM22_transmit_header3, tx_buffer[3]); // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read_noclaim(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | + uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; + rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); - - // Set the tx power - // TODO: Only set the power when it changes and remove this - rfm22_write_noclaim(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | + // set the tx power + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // clear FIFOs - rfm22_write_noclaim(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write_noclaim(RFM22_op_and_func_ctrl2, 0x00); + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); + // ******************* // add some data to the chips TX FIFO before enabling the transmitter + + // set the total number of data bytes we are going to transmit + rfm22_write(RFM22_transmit_packet_length, tx_data_wr); + + // add some data + rfm22_claimBus(); + PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); int bytes_to_write = (tx_data_wr - tx_data_rd); bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write; - rfm22_write_noclaim(RFM22_transmit_packet_length, bytes_to_write); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); - tx_data_rd +=PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + tx_data_rd += bytes_to_write; + rfm22_releaseBus(); + + + // ******************* // reset the timer rfm22_int_timer = 0; @@ -1231,15 +1238,14 @@ uint8_t rfm22_txStart() rf_mode = TX_DATA_MODE; // enable TX interrupts - rfm22_write_noclaim(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); + rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); + // enable the transmitter - rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); TX_LED_ON; - rfm22_releaseBus(); exec_using_spi = false; - return 1; } @@ -1333,7 +1339,6 @@ static void rfm22_setTxMode(uint8_t mode) rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); rfm22_releaseBus(); - TX_LED_ON; } From 113c3d3b769c0921f1ea5cbb9fcc6e4599503fc2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 4 Sep 2012 10:20:51 -0500 Subject: [PATCH 447/508] RM Telem: Make sure it properly tracks the outgoing rate of bytes --- flight/Modules/Telemetry/telemetry.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index a1cc19c34..6c07cb51d 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -381,7 +381,7 @@ static int32_t transmitData(uint8_t * data, int32_t length) #ifdef PIOS_PACKET_HANDLER if (PIOS_PACKET_HANDLER) if (PHTransmitData(PIOS_PACKET_HANDLER, data, length)) - return 0; + return length; #endif return -1; } From 844d14e2f53eb596d8aaaf6fcd8358d2660a5617 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 4 Sep 2012 10:22:04 -0500 Subject: [PATCH 448/508] RM (NOT FOR PIPX) Properly select the GPIO->RX/TX mapping --- flight/PiOS/Common/pios_rfm22b.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 8280a8126..b975561a5 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1970,8 +1970,8 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // choose the 3 GPIO pin functions rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value - rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) - rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) + rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch) + rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch) rfm22_write(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment // **************** From 68fa464ccfebbad72115a960fcf00f41858b2c5d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 4 Sep 2012 23:22:56 -0500 Subject: [PATCH 449/508] RM: Make the direction of the TX/RX lines come from the configuration file --- flight/PiOS/Common/pios_rfm22b.c | 9 +++++++-- flight/PiOS/inc/pios_rfm22b.h | 4 ++++ flight/board_hw_defs/pipxtreme/board_hw_defs.c | 2 ++ flight/board_hw_defs/revomini/board_hw_defs.c | 2 ++ 4 files changed, 15 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index b975561a5..8a1de73de 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1970,8 +1970,13 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // choose the 3 GPIO pin functions rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value - rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch) - rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch) + if (rfm22b_dev_g->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { + rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) + rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) + } else { + rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch) + rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch) + } rfm22_write(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment // **************** diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 31b33a69d..c824af638 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -31,6 +31,8 @@ #ifndef PIOS_RFM22B_H #define PIOS_RFM22B_H +enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX}; + /* Global Types */ struct pios_rfm22b_cfg { const struct pios_spi_cfg * spi_cfg; /* Pointer to SPI interface configuration */ @@ -41,6 +43,8 @@ struct pios_rfm22b_cfg { uint8_t RFXtalCap; uint32_t maxRFBandwidth; uint8_t maxTxPower; + uint8_t slave_num; + enum gpio_direction gpio_direction; }; /* Public Functions */ diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index 30c666f17..16ff720c1 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -228,6 +228,8 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { .RFXtalCap = 0x7f, .maxRFBandwidth = 128000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW + .slave_num = 0, + .gpio_direction = GPIO0_TX_GPIO1_RX, }; #endif /* PIOS_INCLUDE_RFM22B */ diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index af1791291..5516b64f0 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -359,6 +359,8 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { .RFXtalCap = 0x7f, .maxRFBandwidth = 128000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW + .slave_num = 0, + .gpio_direction = GPIO0_RX_GPIO1_TX, }; #endif /* PIOS_INCLUDE_RFM22B */ From 1f0004e9db2f8cee7c09202396c5512f38f4c66e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 5 Sep 2012 00:25:06 -0500 Subject: [PATCH 450/508] RFM22b: Abstract out the port into the driver initiation Also use a separate function to claim the bus semaphore and assert the CS line. --- flight/Modules/Radio/radio.c | 2 +- flight/PiOS/Common/pios_rfm22b.c | 246 ++++++++++++++++--------------- flight/PiOS/inc/pios_rfm22b.h | 2 +- 3 files changed, 132 insertions(+), 118 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index e84f34be3..14e2dafaa 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -234,7 +234,7 @@ static int32_t RadioInitialize(void) /* Initalize the RFM22B radio COM device. */ { - if (PIOS_RFM22B_Init(&pios_rfm22b_id, &pios_rfm22b_cfg)) { + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg.slave_num, &pios_rfm22b_cfg)) { return -1; } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 8a1de73de..a3ec9137e 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -158,6 +158,9 @@ struct pios_rfm22b_dev { enum pios_rfm22b_dev_magic magic; struct pios_rfm22b_cfg cfg; + uint32_t spi_id; + uint32_t slave_num; + uint32_t deviceID; // ISR pending @@ -199,20 +202,14 @@ static void rfm22_processInt(void); static void rfm22_setTxMode(uint8_t mode); // SPI read/write functions -void rfm22_startBurstWrite(uint8_t addr); -inline void rfm22_burstWrite(uint8_t data) -{ - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, data); -} -void rfm22_endBurstWrite(void); -void rfm22_write(uint8_t addr, uint8_t data); -void rfm22_startBurstRead(uint8_t addr); +static void rfm22_write(uint8_t addr, uint8_t data); +static void rfm22_startBurstRead(uint8_t addr); inline uint8_t rfm22_burstRead(void) { return PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); } -void rfm22_endBurstRead(void); -uint8_t rfm22_read(uint8_t addr); +static void rfm22_endBurstRead(void); +static uint8_t rfm22_read(uint8_t addr); uint8_t rfm22_txStart(); /* Provide a COM driver */ @@ -383,7 +380,7 @@ struct pios_rfm22b_dev * rfm22b_dev_g; static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev) { - return (rfm22b_dev->magic == PIOS_RFM22B_DEV_MAGIC); + return (rfm22b_dev != NULL && rfm22b_dev->magic == PIOS_RFM22B_DEV_MAGIC); } #if defined(PIOS_INCLUDE_FREERTOS) @@ -392,6 +389,7 @@ static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) struct pios_rfm22b_dev * rfm22b_dev; rfm22b_dev = (struct pios_rfm22b_dev *)pvPortMalloc(sizeof(*rfm22b_dev)); + rfm22b_dev->spi_id = 0; if (!rfm22b_dev) return(NULL); rfm22b_dev_g = rfm22b_dev; @@ -415,12 +413,12 @@ static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) } #endif -static struct pios_rfm22b_dev * g_rfm22b_dev; +static struct pios_rfm22b_dev * g_rfm22b_dev = NULL; /** * Initialise an RFM22B device */ -int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) +int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg) { PIOS_DEBUG_Assert(rfm22b_id); PIOS_DEBUG_Assert(cfg); @@ -430,6 +428,10 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg) if (!rfm22b_dev) return(-1); + // Store the SPI handle + rfm22b_dev->slave_num = slave_num; + rfm22b_dev->spi_id = spi_id; + // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; @@ -661,46 +663,46 @@ static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id) // ************************************ // SPI read/write +//! Assert the CS line +static void rfm22_assertCs() +{ + PIOS_DELAY_WaituS(1); + if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0) + PIOS_SPI_RC_PinSet(g_rfm22b_dev->spi_id, g_rfm22b_dev->slave_num, 0); +} + +//! Deassert the CS line +static void rfm22_deassertCs() +{ + if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0) + PIOS_SPI_RC_PinSet(g_rfm22b_dev->spi_id, g_rfm22b_dev->slave_num, 1); +} + +//! Claim the SPI bus semaphore static void rfm22_claimBus() { - // chip select line LOW - PIOS_SPI_ClaimBus(PIOS_RFM22_SPI_PORT); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); + if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0) + PIOS_SPI_ClaimBus(g_rfm22b_dev->spi_id); } +//! Release the SPI bus semaphore static void rfm22_releaseBus() { - // chip select line HIGH - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); - PIOS_SPI_ReleaseBus(PIOS_RFM22_SPI_PORT); + if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0) + PIOS_SPI_ReleaseBus(g_rfm22b_dev->spi_id); } -void rfm22_startBurstWrite(uint8_t addr) +//! +static void rfm22_write(uint8_t addr, uint8_t data) { - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - rfm22_claimBus(); - - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); -} - -void rfm22_endBurstWrite(void) -{ - rfm22_releaseBus(); -} - -void rfm22_write(uint8_t addr, uint8_t data) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - rfm22_claimBus(); - - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | addr); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, data); - - rfm22_releaseBus(); + if(PIOS_RFM22B_validate(g_rfm22b_dev)) { + rfm22_claimBus(); + rfm22_assertCs(); + uint8_t buf[2] = {addr | 0x80, data}; + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL); + rfm22_deassertCs(); + rfm22_releaseBus(); + } } /** @@ -710,56 +712,70 @@ void rfm22_write(uint8_t addr, uint8_t data) static void rfm22_write_noclaim(uint8_t addr, uint8_t data) { uint8_t buf[2] = {addr | 0x80, data}; - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, buf, NULL, 2, NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); -} - -void rfm22_startBurstRead(uint8_t addr) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - rfm22_claimBus(); - - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); -} - -void rfm22_endBurstRead(void) -{ - rfm22_releaseBus(); -} - -//! Read a byte from tan address and claim/release the semaphore -uint8_t rfm22_read(uint8_t addr) -{ - uint8_t rdata; - - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - - rfm22_claimBus(); - - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, addr & 0x7f); - rdata = PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); - - rfm22_releaseBus(); - - return rdata; + if(PIOS_RFM22B_validate(g_rfm22b_dev)) { + rfm22_assertCs(); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL); + rfm22_deassertCs(); + } } /** - * Read a byte from a register without claiming the bus. Also - * toggle the NSS line + * Start a burst read a byte from an RFM22b + * @param[in] addr The address to read from + * @return Returns the result of the register read + */ +static void rfm22_startBurstRead(uint8_t addr) +{ + // wait 1us .. so we don't toggle the CS line to quickly + PIOS_DELAY_WaituS(1); + if(PIOS_RFM22B_validate(g_rfm22b_dev)) { + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, addr & 0x7f); + } +} + +//! Release the CS and bus +static void rfm22_endBurstRead(void) +{ + rfm22_deassertCs(); + rfm22_releaseBus(); +} + +/** + * Read a byte from an RFM22b register + * @param[in] addr The address to read from + * @return Returns the result of the register read + */ +static uint8_t rfm22_read(uint8_t addr) +{ + uint8_t in[2]; + uint8_t out[2] = {addr & 0x7f, 0xFF}; + if(PIOS_RFM22B_validate(g_rfm22b_dev)) { + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out, in, sizeof(out), NULL); + rfm22_deassertCs(); + rfm22_releaseBus(); + } + return in[1]; +} + +/** + * Read a byte from an RFM22b register without claiming the bus + * @param[in] addr The address to read from + * @return Returns the result of the register read */ static uint8_t rfm22_read_noclaim(uint8_t addr) { - uint8_t buf[2] = {addr | 0x80, 0xFF}; - uint8_t read[2]; - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, buf, read, 2, NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); - return read[1]; + uint8_t out[2] = {addr & 0x7F, 0xFF}; + uint8_t in[2]; + if (PIOS_RFM22B_validate(rfm22b_dev_g)) { + rfm22_assertCs(); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out, in, sizeof(out), NULL); + rfm22_deassertCs(); + } + return in[1]; } // ************************************ @@ -1222,14 +1238,15 @@ uint8_t rfm22_txStart() // add some data rfm22_claimBus(); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); + rfm22_assertCs(); + PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80); int bytes_to_write = (tx_data_wr - tx_data_rd); bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write; - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); tx_data_rd += bytes_to_write; + rfm22_deassertCs(); rfm22_releaseBus(); - // ******************* // reset the timer @@ -1256,11 +1273,12 @@ static void rfm22_setTxMode(uint8_t mode) return; // invalid mode rfm22_claimBus(); + rfm22_assertCs(); // Disaable interrupts (IE1, IE2 = 0) uint8_t out_buf[3] = {RFM22_interrupt_enable1 | 0x80, 0x00, 0x00}; - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, out_buf, NULL, sizeof(out_buf), NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out_buf, NULL, sizeof(out_buf), NULL); + rfm22_deassertCs(); // TUNE mode rfm22_write_noclaim(RFM22_op_and_func_ctrl1,RFM22_opfc1_pllon); @@ -1300,13 +1318,13 @@ static void rfm22_setTxMode(uint8_t mode) rfm22_write_noclaim(RFM22_transmit_packet_length, wr); uint16_t i = 0; - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0x80 | RFM22_fifo_access); // Initiate burst write + rfm22_assertCs(); + PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, 0x80 | RFM22_fifo_access); // Initiate burst write if (mode == TX_STREAM_MODE) { if (rd >= wr) - i += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, FULL_PREAMBLE, NULL, sizeof(FULL_PREAMBLE), NULL); + i += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, FULL_PREAMBLE, NULL, sizeof(FULL_PREAMBLE), NULL); else // add the RF heaader - i += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, HEADER, NULL, sizeof(HEADER), NULL); + i += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, HEADER, NULL, sizeof(HEADER), NULL); } // Send data if there is any and there is space in the buffer available @@ -1314,9 +1332,9 @@ static void rfm22_setTxMode(uint8_t mode) int32_t bytes_to_send = wr - rd; bytes_to_send = ((bytes_to_send + i)> FIFO_SIZE) ? (FIFO_SIZE - i) : bytes_to_send; if (bytes_to_send > 0) - rd += PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[rd], NULL, bytes_to_send, NULL); + rd += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rd], NULL, bytes_to_send, NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_deassertCs(); tx_data_rd = rd; } @@ -1523,11 +1541,13 @@ void rfm22_processTxInt(void) // top-up the rf chips TX FIFO buffer uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; rfm22_claimBus(); - PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, RFM22_fifo_access | 0x80); + rfm22_assertCs(); + PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80); int bytes_to_write = (tx_data_wr - tx_data_rd); bytes_to_write = (bytes_to_write > max_bytes) ? max_bytes: bytes_to_write; - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); tx_data_rd += bytes_to_write; + rfm22_deassertCs(); rfm22_releaseBus(); } @@ -1548,10 +1568,8 @@ void rfm22_processTxInt(void) static void rfm22_processInt(void) { - // this is called from the external interrupt handler - - if (!initialized || power_on_reset) - // we haven't yet been initialized + // we haven't yet been initialized + if (!initialized || power_on_reset || !PIOS_RFM22B_validate(rfm22b_dev_g)) return; exec_using_spi = true; @@ -1563,23 +1581,19 @@ static void rfm22_processInt(void) rfm22_claimBus(); // Set RC and the semaphore uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF}; uint8_t read_buf[3]; - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, sizeof(write_buf), NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); + rfm22_assertCs(); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL); + rfm22_deassertCs(); int_status1 = read_buf[1]; int_status2 = read_buf[2]; // Device status - write_buf[0] = RFM22_device_status & 0x7f; - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, 2, NULL); - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 1); - device_status = read_buf[1]; + device_status = rfm22_read_noclaim(RFM22_device_status); // EzMAC status - write_buf[0] = RFM22_ezmac_status & 0x7f; - PIOS_SPI_RC_PinSet(PIOS_RFM22_SPI_PORT, 0, 0); - PIOS_SPI_TransferBlock(PIOS_RFM22_SPI_PORT, write_buf, read_buf, 2, NULL); - ezmac_status = read_buf[1]; + ezmac_status = rfm22_read_noclaim(RFM22_ezmac_status); + + // Release the bus rfm22_releaseBus(); // Read the RSSI if we're in RX mode diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index c824af638..176b25710 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -48,7 +48,7 @@ struct pios_rfm22b_cfg { }; /* Public Functions */ -extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, const struct pios_rfm22b_cfg *cfg); +extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); From 527edcbee9ef89269d3e87755b99be4c675e168d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 5 Sep 2012 00:56:48 -0500 Subject: [PATCH 451/508] RFM22b: Get rid of the burst read commands and do a block transfer --- flight/PiOS/Common/pios_rfm22b.c | 88 +++++++++++++++----------------- 1 file changed, 42 insertions(+), 46 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index a3ec9137e..9a39765a0 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -195,6 +195,14 @@ static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE,PREAMBLE_BYTE}; // 64 bytes static const uint8_t HEADER[(TX_PREAMBLE_NIBBLES + 1)/2 + 2] = {PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE, PREAMBLE_BYTE,PREAMBLE_BYTE, PREAMBLE_BYTE, SYNC_BYTE_1, SYNC_BYTE_2}; +static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, + 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF}; /* Local function forwared declarations */ static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); @@ -203,12 +211,6 @@ static void rfm22_setTxMode(uint8_t mode); // SPI read/write functions static void rfm22_write(uint8_t addr, uint8_t data); -static void rfm22_startBurstRead(uint8_t addr); -inline uint8_t rfm22_burstRead(void) -{ - return PIOS_SPI_TransferByte(PIOS_RFM22_SPI_PORT, 0xff); -} -static void rfm22_endBurstRead(void); static uint8_t rfm22_read(uint8_t addr); uint8_t rfm22_txStart(); @@ -692,7 +694,11 @@ static void rfm22_releaseBus() PIOS_SPI_ReleaseBus(g_rfm22b_dev->spi_id); } -//! +/** + * Claim the semaphore and write a byte to a register + * @param[in] addr The address to write to + * @param[in] data The datat to write to that address + */ static void rfm22_write(uint8_t addr, uint8_t data) { if(PIOS_RFM22B_validate(g_rfm22b_dev)) { @@ -708,6 +714,8 @@ static void rfm22_write(uint8_t addr, uint8_t data) /** * Write a byte to a register without claiming the bus. Also * toggle the NSS line + * @param[in] addr The address of the RFM22b register to write + * @param[in] data The data to write to that register */ static void rfm22_write_noclaim(uint8_t addr, uint8_t data) { @@ -720,29 +728,7 @@ static void rfm22_write_noclaim(uint8_t addr, uint8_t data) } /** - * Start a burst read a byte from an RFM22b - * @param[in] addr The address to read from - * @return Returns the result of the register read - */ -static void rfm22_startBurstRead(uint8_t addr) -{ - // wait 1us .. so we don't toggle the CS line to quickly - PIOS_DELAY_WaituS(1); - if(PIOS_RFM22B_validate(g_rfm22b_dev)) { - rfm22_claimBus(); - rfm22_assertCs(); - PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, addr & 0x7f); - } -} -//! Release the CS and bus -static void rfm22_endBurstRead(void) -{ - rfm22_deassertCs(); - rfm22_releaseBus(); -} - -/** * Read a byte from an RFM22b register * @param[in] addr The address to read from * @return Returns the result of the register read @@ -1427,17 +1413,22 @@ void rfm22_processRxInt(void) } // Fetch the data from the RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - for (uint8_t i = 0; i < RX_FIFO_HI_WATERMARK; ++i) - rx_buffer[rx_buffer_wr++] = rfm22_burstRead(); - rfm22_endBurstRead(); - } - else - { // just clear the RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--) - rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer - rfm22_endBurstRead(); + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); + rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF, + (uint8_t *) &rx_buffer[rx_buffer_wr],RX_FIFO_HI_WATERMARK,NULL) == 0) ? + RX_FIFO_HI_WATERMARK : 0; + rfm22_deassertCs(); + rfm22_releaseBus(); + } else { + // Clear the RX FIFO + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); + PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF,NULL,RX_FIFO_HI_WATERMARK,NULL); + rfm22_deassertCs(); + rfm22_releaseBus(); } } @@ -1454,18 +1445,23 @@ void rfm22_processRxInt(void) { // read the total length of the packet data - register uint16_t len = rfm22_read(RFM22_received_packet_length); + uint32_t len = rfm22_read(RFM22_received_packet_length); // their must still be data in the RX FIFO we need to get if (rx_buffer_wr < len) { + int32_t bytes_to_read = len - rx_buffer_wr; // Fetch the data from the RX FIFO - rfm22_startBurstRead(RFM22_fifo_access); - while (rx_buffer_wr < len) - rx_buffer[rx_buffer_wr++] = rfm22_burstRead(); - rfm22_endBurstRead(); + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); + rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF, + (uint8_t *) &rx_buffer[rx_buffer_wr],bytes_to_read,NULL) == 0) ? + bytes_to_read : 0; + rfm22_deassertCs(); + rfm22_releaseBus(); } - + if (rx_buffer_wr != len) { // we have a packet length error .. discard the packet From f3f07682ac980a044ac68780095b56f838381ab6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 8 Sep 2012 02:25:39 -0500 Subject: [PATCH 452/508] RFM22b radio.c: Increase the stack side for the status task which runs the ISR --- flight/Modules/Radio/radio.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 14e2dafaa..b72f3ea12 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -136,7 +136,7 @@ static int32_t RadioStart(void) // Start the tasks. xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle)); - xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); + xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES * 2, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); xTaskCreate(sendPacketTask, (signed char *)"SendPacket", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle)); // Install the monitors From 5211176f15889bc8c9c4a2687539301a3139dffa Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 10 Sep 2012 20:12:23 -0500 Subject: [PATCH 453/508] ManualControl: Cover the case for PathPlanner to avoid setting an alarm. No functional change. --- flight/Modules/ManualControl/manualcontrol.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 63db0833a..27454462a 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -431,6 +431,9 @@ static void manualControlTask(void *parameters) case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + // Nothing to do + break; case FLIGHTSTATUS_FLIGHTMODE_RTH: setRTH(lastFlightMode != flightStatus.FlightMode); break; From aaaf23e64c3def57d829d2690a756ad8a7cf03f9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 10 Sep 2012 20:12:23 -0500 Subject: [PATCH 454/508] ManualControl: Cover the case for PathPlanner to avoid setting an alarm. No functional change. --- flight/Modules/ManualControl/manualcontrol.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 2416621f7..be773a08b 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -427,6 +427,9 @@ static void manualControlTask(void *parameters) case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + // Nothing to do + break; case FLIGHTSTATUS_FLIGHTMODE_RTH: setRTH(lastFlightMode != flightStatus.FlightMode); break; From 316e02612efcd89fbfd4c473c5708c8fa540d097 Mon Sep 17 00:00:00 2001 From: a*morale Date: Tue, 31 Jul 2012 21:54:19 +0200 Subject: [PATCH 455/508] mapped LED1&2 ports to output 9&10 so that it is possible to use as accessory or pwm buzzer --- flight/Revolution/System/pios_board.c | 1 + .../board_hw_defs/revolution/board_hw_defs.c | 93 +++++++++++++++---- 2 files changed, 74 insertions(+), 20 deletions(-) diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index b098f3cd0..4c1282e99 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -421,6 +421,7 @@ void PIOS_Board_Init(void) { /* Set up pulse timers */ PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_2_cfg); PIOS_TIM_InitClock(&tim_3_cfg); PIOS_TIM_InitClock(&tim_4_cfg); PIOS_TIM_InitClock(&tim_5_cfg); diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index 2bc703cd8..68370747b 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -1313,13 +1313,14 @@ void PIOS_RTC_IRQ_Handler (void) #include "pios_tim_priv.h" -static const TIM_TimeBaseInitTypeDef tim_3_5_time_base = { +static const TIM_TimeBaseInitTypeDef tim_2_3_5_time_base = { .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, .TIM_CounterMode = TIM_CounterMode_Up, .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), .TIM_RepetitionCounter = 0x0000, }; + static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = { .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, @@ -1328,9 +1329,43 @@ static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = { .TIM_RepetitionCounter = 0x0000, }; +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_1_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_4_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + + + +static const struct pios_tim_clock_cfg tim_2_cfg = { + .timer = TIM2, + .time_base_init = &tim_2_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + + static const struct pios_tim_clock_cfg tim_3_cfg = { .timer = TIM3, - .time_base_init = &tim_3_5_time_base, + .time_base_init = &tim_2_3_5_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM3_IRQn, @@ -1341,9 +1376,10 @@ static const struct pios_tim_clock_cfg tim_3_cfg = { }, }; + static const struct pios_tim_clock_cfg tim_5_cfg = { .timer = TIM5, - .time_base_init = &tim_3_5_time_base, + .time_base_init = &tim_2_3_5_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM5_IRQn, @@ -1393,23 +1429,6 @@ static const struct pios_tim_clock_cfg tim_11_cfg = { }, }; -// Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_1_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, -}; -// Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_4_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, -}; - static const struct pios_tim_clock_cfg tim_1_cfg = { .timer = TIM1, .time_base_init = &tim_1_time_base, @@ -1569,6 +1588,40 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { }, .remap = GPIO_AF_TIM3, }, + // PB3 - TIM2 CH2 LED1 Ok + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource3, + }, + .remap = GPIO_AF_TIM2, + }, + // led PB4 - TIM3 CH1 LED2 + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource4, + }, + .remap = GPIO_AF_TIM3, + }, }; const struct pios_servo_cfg pios_servo_cfg = { From cf7aea6499201064afae919684b887ba6304b98b Mon Sep 17 00:00:00 2001 From: a*morale Date: Tue, 11 Sep 2012 00:23:49 +0200 Subject: [PATCH 456/508] Support for Led Outputs as actuator channels 9&10. Added the ARMING LED and INFO LED option for actuator channel --- flight/Modules/Actuator/actuator.c | 119 ++++++++++++++---- .../board_hw_defs/revolution/board_hw_defs.c | 4 +- .../uavobjectdefinition/actuatorsettings.xml | 2 +- 3 files changed, 96 insertions(+), 29 deletions(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index e59d50957..c8a993c6b 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -565,28 +565,82 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSet static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings) { switch(actuatorSettings->ChannelType[mixer_channel]) { - case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: { + case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: + case ACTUATORSETTINGS_CHANNELTYPE_ARMINGLED: + case ACTUATORSETTINGS_CHANNELTYPE_INFOLED: + { // This is for buzzers that take a PWM input static uint32_t currBuzzTune = 0; static uint32_t currBuzzTuneState; - uint32_t bewBuzzTune; - // Decide what tune to play - if (AlarmsGet(SYSTEMALARMS_ALARM_BATTERY) > SYSTEMALARMS_ALARM_WARNING) { - bewBuzzTune = 0b11110110110000; // pause, short, short, short, long - } else if (AlarmsGet(SYSTEMALARMS_ALARM_GPS) >= SYSTEMALARMS_ALARM_WARNING) { - bewBuzzTune = 0x80000000; // pause, short - } else { - bewBuzzTune = 0; - } + static uint32_t currArmingTune = 0; + static uint32_t currArmingTuneState; - // Do we need to change tune? - if (bewBuzzTune != currBuzzTune) { - currBuzzTune = bewBuzzTune; - currBuzzTuneState = currBuzzTune; - } + static uint32_t currInfoTune = 0; + static uint32_t currInfoTuneState; + uint32_t newTune = 0; + if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER) + { + + // Decide what tune to play + if (AlarmsGet(SYSTEMALARMS_ALARM_BATTERY) > SYSTEMALARMS_ALARM_WARNING) { + newTune = 0b11110110110000; // pause, short, short, short, long + } else if (AlarmsGet(SYSTEMALARMS_ALARM_GPS) >= SYSTEMALARMS_ALARM_WARNING) { + newTune = 0x80000000; // pause, short + } else { + newTune = 0; + } + + // Do we need to change tune? + if (newTune != currBuzzTune) { + currBuzzTune = newTune; + currBuzzTuneState = currBuzzTune; + } + } + else // ACTUATORSETTINGS_CHANNELTYPE_ARMINGLED || ACTUATORSETTINGS_CHANNELTYPE_INFOLED + { + uint8_t arming; + FlightStatusArmedGet(&arming); + //base idle tune + newTune = 0x80000000; // 0b1000... + + // Merge the error pattern for InfoLed + if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_INFOLED) + { + if (AlarmsGet(SYSTEMALARMS_ALARM_BATTERY) > SYSTEMALARMS_ALARM_WARNING) + { + newTune |= 0b00000000001111111011111110000000; + } + else if(AlarmsGet(SYSTEMALARMS_ALARM_GPS) >= SYSTEMALARMS_ALARM_WARNING) + { + newTune |= 0b00000000000000110110110000000000; + } + } + // fast double blink pattern if armed + if (arming == FLIGHTSTATUS_ARMED_ARMED) + newTune |= 0xA0000000; // 0b101000... + + // Do we need to change tune? + if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_ARMINGLED) + { + if (newTune != currArmingTune) { + currArmingTune = newTune; + // note: those are both updated so that Info and Arming are in sync if used simultaneously + currArmingTuneState = currArmingTune; + currInfoTuneState = currInfoTune; + } + } + else + { + if (newTune != currInfoTune) { + currInfoTune = newTune; + currArmingTuneState = currArmingTune; + currInfoTuneState = currInfoTune; + } + } + } // Play tune bool buzzOn = false; @@ -595,17 +649,30 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSet portTickType dT = 0; // For now, only look at the battery alarm, because functions like AlarmsHasCritical() can block for some time; to be discussed - if (currBuzzTune) { - if(thisSysTime > lastSysTime) - dT = thisSysTime - lastSysTime; - buzzOn = (currBuzzTuneState&1); // Buzz when the LS bit is 1 - if (dT > 80) { - // Go to next bit in alarm_seq_state - currBuzzTuneState >>= 1; - if (currBuzzTuneState == 0) - currBuzzTuneState = currBuzzTune; // All done, re-start the tune - lastSysTime = thisSysTime; - } + if (currBuzzTune||currArmingTune||currInfoTune) { + if(thisSysTime > lastSysTime) + dT = thisSysTime - lastSysTime; + if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER) + buzzOn = (currBuzzTuneState&1); // Buzz when the LS bit is 1 + else if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_ARMINGLED) + buzzOn = (currArmingTuneState&1); + else if(actuatorSettings->ChannelType[mixer_channel] == ACTUATORSETTINGS_CHANNELTYPE_INFOLED) + buzzOn = (currInfoTuneState&1); + + if (dT > 80) { + // Go to next bit in alarm_seq_state + currArmingTuneState >>=1; + currInfoTuneState >>= 1; + currBuzzTuneState >>= 1; + + if (currBuzzTuneState == 0) + currBuzzTuneState = currBuzzTune; // All done, re-start the tune + if (currArmingTuneState == 0) + currArmingTuneState = currArmingTune; + if (currInfoTuneState == 0) + currInfoTuneState = currInfoTune; + lastSysTime = thisSysTime; + } } PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], buzzOn?actuatorSettings->ChannelMax[mixer_channel]:actuatorSettings->ChannelMin[mixer_channel]); diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/board_hw_defs/revolution/board_hw_defs.c index 68370747b..ffc61f989 100644 --- a/flight/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/board_hw_defs/revolution/board_hw_defs.c @@ -1588,7 +1588,7 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { }, .remap = GPIO_AF_TIM3, }, - // PB3 - TIM2 CH2 LED1 Ok + // PB3 - TIM2 CH2 LED1 { .timer = TIM2, .timer_chan = TIM_Channel_2, @@ -1605,7 +1605,7 @@ static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { }, .remap = GPIO_AF_TIM2, }, - // led PB4 - TIM3 CH1 LED2 + // PB4 - TIM3 CH1 LED2 { .timer = TIM3, .timer_chan = TIM_Channel_1, diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml index 7f438a22c..2dd3b14bd 100644 --- a/shared/uavobjectdefinition/actuatorsettings.xml +++ b/shared/uavobjectdefinition/actuatorsettings.xml @@ -5,7 +5,7 @@ - + From 4cbaa6df8841d1b691be2800791e5e37dbb33ec6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 11 Sep 2012 01:44:40 -0500 Subject: [PATCH 457/508] Revolution: Misses some files for stabilization refactoring in Revolution --- flight/Revolution/Makefile | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index 88d154ba5..77012ec0e 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -72,6 +72,8 @@ PIOSINC = $(PIOS)/inc OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = ../Libraries/inc +MATHLIB = ../Libraries/math +MATHLIBINC = ../Libraries/math PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -141,6 +143,8 @@ SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(MATHLIB)/sin_lookup.c +SRC += $(MATHLIB)/pid.c ## PIOS Hardware (STM32F4xx) include $(PIOS)/STM32F4xx/library.mk @@ -203,6 +207,7 @@ EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(MATHLIBINC) EXTRAINCDIRS += $(PIOSSTM32F4XX) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) From 88b483f37d753f6145580a6a5f20842aae43ea19 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 11 Sep 2012 01:45:15 -0500 Subject: [PATCH 458/508] PIOS_MPU6000: Make the driver perform the rotation to bring it into the OP coordinate system Previously there were hacks spread throughout to deal with various ways of positioning the chips. Now the driver structure specifies the rotation of the chip relative to the board layout and the output X/Y/Z are already in OP convention. This flag seems to do the right thing for Revolution, CC3D, and RevoMini --- flight/CopterControl/System/pios_board.c | 3 +- flight/Modules/Attitude/attitude.c | 12 ++--- flight/Modules/Sensors/sensors.c | 32 ++++++------- flight/PiOS/Common/pios_mpu6000.c | 61 ++++++++++++++++++++---- flight/PiOS/inc/pios_mpu6000.h | 8 ++++ flight/RevoMini/System/pios_board.c | 3 +- flight/Revolution/System/pios_board.c | 3 +- 7 files changed, 89 insertions(+), 33 deletions(-) diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index f59e7335a..1b6770820 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -114,7 +114,8 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, .accel_range = PIOS_MPU6000_ACCEL_8G, .gyro_range = PIOS_MPU6000_SCALE_500_DEG, - .filter = PIOS_MPU6000_LOWPASS_256_HZ + .filter = PIOS_MPU6000_LOWPASS_256_HZ, + .orientation = PIOS_MPU6000_TOP_180DEG }; #endif /* PIOS_INCLUDE_MPU6000 */ diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 6b0c16cec..d7597aa88 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -379,13 +379,13 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) if (GyrosReadOnly() || AccelsReadOnly()) return 0; - gyros[0] = -mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); - gyros[1] = -mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); - gyros[2] = -mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); + gyros[0] = mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); + gyros[1] = mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); + gyros[2] = mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); - accels[0] = -mpu6000_data.accel_y * PIOS_MPU6000_GetAccelScale(); - accels[1] = -mpu6000_data.accel_x * PIOS_MPU6000_GetAccelScale(); - accels[2] = -mpu6000_data.accel_z * PIOS_MPU6000_GetAccelScale(); + accels[0] = mpu6000_data.accel_x * PIOS_MPU6000_GetAccelScale(); + accels[1] = mpu6000_data.accel_y * PIOS_MPU6000_GetAccelScale(); + accels[2] = mpu6000_data.accel_z * PIOS_MPU6000_GetAccelScale(); gyrosData->temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; accelsData->temperature = 35.0f + ((float) mpu6000_data.temperature + 512.0f) / 340.0f; diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index b9c3159de..9f16fb5f9 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -259,9 +259,9 @@ static void SensorsTask(void *parameters) while(read_good == 0) { count++; - accel_accum[0] += accel.x; - accel_accum[1] += accel.y; - accel_accum[2] += accel.z; + accel_accum[1] += accel.x; + accel_accum[0] += accel.y; + accel_accum[2] -= accel.z; read_good = PIOS_BMA180_ReadFifo(&accel); } @@ -284,9 +284,9 @@ static void SensorsTask(void *parameters) } gyro_samples = 1; - gyro_accum[0] += gyro.gyro_x; - gyro_accum[1] += gyro.gyro_y; - gyro_accum[2] += gyro.gyro_z; + gyro_accum[1] += gyro.gyro_x; + gyro_accum[0] += gyro.gyro_y; + gyro_accum[2] -= gyro.gyro_z; gyro_scaling = PIOS_L3GD20_GetScale(); @@ -303,12 +303,12 @@ static void SensorsTask(void *parameters) while(xQueueReceive(queue, (void *) &mpu6000_data, gyro_samples == 0 ? 10 : 0) != errQUEUE_EMPTY) { - gyro_accum[0] += -mpu6000_data.gyro_x; - gyro_accum[1] += -mpu6000_data.gyro_y; + gyro_accum[0] += mpu6000_data.gyro_x; + gyro_accum[1] += mpu6000_data.gyro_y; gyro_accum[2] += mpu6000_data.gyro_z; - accel_accum[0] += -mpu6000_data.accel_x; - accel_accum[1] += -mpu6000_data.accel_y; + accel_accum[0] += mpu6000_data.accel_x; + accel_accum[1] += mpu6000_data.accel_y; accel_accum[2] += mpu6000_data.accel_z; gyro_samples ++; @@ -334,9 +334,9 @@ static void SensorsTask(void *parameters) } // Scale the accels - float accels[3] = {(float) accel_accum[1] / accel_samples, - (float) accel_accum[0] / accel_samples, - -(float) accel_accum[2] / accel_samples}; + float accels[3] = {(float) accel_accum[0] / accel_samples, + (float) accel_accum[1] / accel_samples, + (float) accel_accum[2] / accel_samples}; float accels_out[3] = {accels[0] * accel_scaling * accel_scale[0] - accel_bias[0], accels[1] * accel_scaling * accel_scale[1] - accel_bias[1], accels[2] * accel_scaling * accel_scale[2] - accel_bias[2]}; @@ -353,9 +353,9 @@ static void SensorsTask(void *parameters) AccelsSet(&accelsData); // Scale the gyros - float gyros[3] = {(float) gyro_accum[1] / gyro_samples, - (float) gyro_accum[0] / gyro_samples, - -(float) gyro_accum[2] / gyro_samples}; + float gyros[3] = {(float) gyro_accum[0] / gyro_samples, + (float) gyro_accum[1] / gyro_samples, + (float) gyro_accum[2] / gyro_samples}; float gyros_out[3] = {gyros[0] * gyro_scaling, gyros[1] * gyro_scaling, gyros[2] * gyro_scaling}; diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c index 904e9402c..f1e39712f 100644 --- a/flight/PiOS/Common/pios_mpu6000.c +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -276,6 +276,7 @@ static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data) */ int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data) { + // THIS FUNCTION IS DEPRECATED AND DOES NOT PERFORM A ROTATION uint8_t buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0}; uint8_t rec[7]; @@ -451,19 +452,63 @@ void PIOS_MPU6000_IRQHandler(void) PIOS_MPU6000_ReleaseBus(); } + // Rotate the sensor to OP convention. The datasheet defines X as towards the right + // and Y as forward. OP convention transposes this. Also the Z is defined negatively + // to our convention #if defined(PIOS_MPU6000_ACCEL) - data.accel_x = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; - data.accel_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; - data.accel_z = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; + // Currently we only support rotations on top so switch X/Y accordingly + switch(dev->cfg->orientation) { + case PIOS_MPU6000_TOP_0DEG: + data.accel_y = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; // chip X + data.accel_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip Y + data.gyro_y = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; // chip X + data.gyro_x = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; // chip Y + break; + case PIOS_MPU6000_TOP_90DEG: + data.accel_y = -(mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip Y + data.accel_x = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; // chip X + data.gyro_y = -(mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]); // chip Y + data.gyro_x = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; // chip X + break; + case PIOS_MPU6000_TOP_180DEG: + data.accel_y = -(mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]); // chip X + data.accel_x = -(mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip Y + data.gyro_y = -(mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]); // chip X + data.gyro_x = -(mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]); // chip Y + break; + case PIOS_MPU6000_TOP_270DEG: + data.accel_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip Y + data.accel_x = -(mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]); // chip X + data.gyro_y = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; // chip Y + data.gyro_x = -(mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]); // chip X + break; + } + data.gyro_z = -(mpu6000_rec_buf[13] << 8 | mpu6000_rec_buf[14]); + data.accel_z = -(mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]); data.temperature = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; - data.gyro_x = mpu6000_rec_buf[9] << 8 | mpu6000_rec_buf[10]; - data.gyro_y = mpu6000_rec_buf[11] << 8 | mpu6000_rec_buf[12]; - data.gyro_z = mpu6000_rec_buf[13] << 8 | mpu6000_rec_buf[14]; #else - data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; data.gyro_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; - data.gyro_z = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; + switch(dev->cfg->orientation) { + case PIOS_MPU6000_TOP_0DEG: + data.gyro_y = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; + data.gyro_x = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; + break; + case PIOS_MPU6000_TOP_90DEG: + data.gyro_y = -(mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]); // chip Y + data.gyro_x = mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]; // chip X + break; + case PIOS_MPU6000_TOP_180DEG: + data.gyro_y = -(mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); + data.gyro_x = -(mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]); + break; + case PIOS_MPU6000_TOP_270DEG: + data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; // chip Y + data.gyro_x = -(mpu6000_rec_buf[3] << 8 | mpu6000_rec_buf[4]); // chip X + break; + } + data.gyro_z = -(mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]); + data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; #endif xQueueSend(dev->queue, (void *) &data, 0); diff --git a/flight/PiOS/inc/pios_mpu6000.h b/flight/PiOS/inc/pios_mpu6000.h index 317b8155b..b8a49a1ad 100644 --- a/flight/PiOS/inc/pios_mpu6000.h +++ b/flight/PiOS/inc/pios_mpu6000.h @@ -123,6 +123,13 @@ enum pios_mpu6000_accel_range { PIOS_MPU6000_ACCEL_16G = 0x18 }; +enum pios_mpu6000_orientation { // clockwise rotation from board forward + PIOS_MPU6000_TOP_0DEG = 0x00, + PIOS_MPU6000_TOP_90DEG = 0x01, + PIOS_MPU6000_TOP_180DEG = 0x02, + PIOS_MPU6000_TOP_270DEG = 0x03 +}; + struct pios_mpu6000_data { int16_t gyro_x; int16_t gyro_y; @@ -147,6 +154,7 @@ struct pios_mpu6000_cfg { enum pios_mpu6000_accel_range accel_range; enum pios_mpu6000_range gyro_range; enum pios_mpu6000_filter filter; + enum pios_mpu6000_orientation orientation; }; /* Public Functions */ diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 89ff48e58..76a81ce9f 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -183,7 +183,8 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, .accel_range = PIOS_MPU6000_ACCEL_8G, .gyro_range = PIOS_MPU6000_SCALE_500_DEG, - .filter = PIOS_MPU6000_LOWPASS_256_HZ + .filter = PIOS_MPU6000_LOWPASS_256_HZ, + .orientation = PIOS_MPU6000_TOP_180DEG }; #endif /* PIOS_INCLUDE_MPU6000 */ diff --git a/flight/Revolution/System/pios_board.c b/flight/Revolution/System/pios_board.c index b098f3cd0..a1f12f244 100644 --- a/flight/Revolution/System/pios_board.c +++ b/flight/Revolution/System/pios_board.c @@ -224,7 +224,8 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = { .Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK, .accel_range = PIOS_MPU6000_ACCEL_8G, .gyro_range = PIOS_MPU6000_SCALE_500_DEG, - .filter = PIOS_MPU6000_LOWPASS_256_HZ + .filter = PIOS_MPU6000_LOWPASS_256_HZ, + .orientation = PIOS_MPU6000_TOP_0DEG }; #endif /* PIOS_INCLUDE_MPU6000 */ From 86422b8b9e8ab1136806277cc5f4384cb3e3c7c0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 11 Sep 2012 02:34:31 -0500 Subject: [PATCH 459/508] VtolPathFollower: Make sure to clear the alarm when running so it doesn't show as uninintialized --- flight/Modules/VtolPathFollower/vtolpathfollower.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 65e3bb812..ddc5a33dc 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -238,6 +238,9 @@ static void vtolPathFollowerTask(void *parameters) break; } + + AlarmsClear(SYSTEMALARMS_ALARM_GUIDANCE); + } } From 6f9f737c359c877c4f5553f58c966052bff810bb Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sun, 16 Sep 2012 22:17:25 -0400 Subject: [PATCH 460/508] gcs uavo: remove obsolete UAVOs from project for GCS --- ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 474257c7b..40d1f05d5 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -71,8 +71,6 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/velocitydesired.h \ $$UAVOBJECT_SYNTHETICS/velocityactual.h \ $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.h \ - $$UAVOBJECT_SYNTHETICS/guidancesettings.h \ - $$UAVOBJECT_SYNTHETICS/positiondesired.h \ $$UAVOBJECT_SYNTHETICS/relaytuning.h \ $$UAVOBJECT_SYNTHETICS/relaytuningsettings.h \ $$UAVOBJECT_SYNTHETICS/ratedesired.h \ @@ -149,8 +147,6 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/velocitydesired.cpp \ $$UAVOBJECT_SYNTHETICS/velocityactual.cpp \ $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/guidancesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/positiondesired.cpp \ $$UAVOBJECT_SYNTHETICS/relaytuningsettings.cpp \ $$UAVOBJECT_SYNTHETICS/relaytuning.cpp \ $$UAVOBJECT_SYNTHETICS/ratedesired.cpp \ From 497683e571a1a92ae8c34ed4f16641631c8e0532 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 18 Sep 2012 13:27:41 -0500 Subject: [PATCH 461/508] Fix OSX simulator --- flight/PiOS.osx/inc/pios_servo.h | 2 +- flight/PiOS.osx/osx/pios_servo.c | 2 +- flight/Revolution/Makefile.osx | 7 +++++++ 3 files changed, 9 insertions(+), 2 deletions(-) diff --git a/flight/PiOS.osx/inc/pios_servo.h b/flight/PiOS.osx/inc/pios_servo.h index 7cbf37a7d..952baa5a0 100644 --- a/flight/PiOS.osx/inc/pios_servo.h +++ b/flight/PiOS.osx/inc/pios_servo.h @@ -32,7 +32,7 @@ /* Public Functions */ extern void PIOS_Servo_Init(void); -extern void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t num_banks); +extern void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t num_banks); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); #endif /* PIOS_SERVO_H */ diff --git a/flight/PiOS.osx/osx/pios_servo.c b/flight/PiOS.osx/osx/pios_servo.c index 93b86a1ed..d0cf530d3 100644 --- a/flight/PiOS.osx/osx/pios_servo.c +++ b/flight/PiOS.osx/osx/pios_servo.c @@ -50,7 +50,7 @@ void PIOS_Servo_Init(void) * \param[in] onetofour Rate for outputs 1 to 4 (Hz) * \param[in] fivetoeight Rate for outputs 5 to 8 (Hz) */ -void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks) +void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks) { } diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index a38bced0d..e57bf7969 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -92,6 +92,8 @@ OPTESTS = ./Tests OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = ../Libraries/math +MATHLIBINC = ../Libraries/math PIOS = ../PiOS.osx PIOSINC = $(PIOS)/inc PIOSPOSIX = $(PIOS)/osx @@ -186,6 +188,9 @@ SRC += $(FLIGHTLIB)/CoordinateConversions.c SRC += $(FLIGHTLIB)/paths.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(MATHLIB)/pid.c +SRC += $(MATHLIB)/sin_lookup.c + ## RTOS and RTOS Portable SRC += $(RTOSSRCDIR)/list.c @@ -225,6 +230,8 @@ EXTRAINCDIRS += $(UAVOBJSYNTHDIR) EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(MATHLIBINC) +EXTRAINCDIRS += $(FLIGTH) EXTRAINCDIRS += $(PIOSPOSIX) EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) From 432a6dfd000fec3b69f5a4eeb1222b48b9ad5117 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sat, 8 Sep 2012 12:02:00 -0700 Subject: [PATCH 462/508] RM: Fixed crashing when radio module is disabled. --- flight/Modules/Telemetry/telemetry.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index 6c07cb51d..21fe81867 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -264,7 +264,7 @@ static void processObjEvent(UAVObjEvent * ev) if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL || ((ev->event == EV_UPDATED_PERIODIC) && (updateMode != UPDATEMODE_THROTTLED))) { #ifdef PIOS_PACKET_HANDLER // Don't send PipXStatus objects over the radio link. - if ((ev->obj == PipXStatusHandle()) && (getComPort() == 0) && PIOS_PACKET_HANDLER) + if (PIOS_PACKET_HANDLER && (ev->obj == PipXStatusHandle()) && (getComPort() == 0)) return; #endif // Send update to GCS (with retries) From 6623c55846aa01e7577ac59b04643e25b891cce6 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 11 Sep 2012 20:34:26 -0700 Subject: [PATCH 463/508] RFM22B: Moved ISR processing thread into the rfm22b driver. --- flight/Modules/Radio/radio.c | 11 ++---- flight/PiOS/Common/pios_rfm22b.c | 60 +++++++++++++++++++++++--------- 2 files changed, 46 insertions(+), 25 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index b72f3ea12..65650d815 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -441,11 +441,9 @@ static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) */ static void radioStatusTask(void *parameters) { - static portTickType lastSysTime; PHStatusPacket status_packet; - while (1) { - lastSysTime = xTaskGetTickCount(); + while (1) { PipXStatusData pipxStatus; uint32_t pairID; @@ -524,12 +522,7 @@ static void radioStatusTask(void *parameters) } } - portTickType timeSinceUpdate; - do { - PIOS_RFM22_processPendingISR(5); - timeSinceUpdate = xTaskGetTickCount() - lastSysTime; - } - while(timeSinceUpdate < STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); + vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); } } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 9a39765a0..6029d8488 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -56,7 +56,9 @@ #include /* Local Defines */ -#define STACK_SIZE_BYTES 200 +#define STACK_SIZE_BYTES 200 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 2) +#define ISR_TIMEOUT 5 // ms // RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). // A 256 byte message at 56kbps should take less than 40ms @@ -163,6 +165,9 @@ struct pios_rfm22b_dev { uint32_t deviceID; + // The task handle + xTaskHandle taskHandle; + // ISR pending xSemaphoreHandle isrPending; @@ -175,6 +180,10 @@ struct pios_rfm22b_dev { // The supervisor countdown timer. uint16_t supv_timer; uint16_t resets; + + // Stats + uint32_t rfm32_errors; + uint32_t rfm32_irqs_processed; }; uint32_t random32 = 0x459ab8d8; @@ -206,6 +215,7 @@ static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, /* Local function forwared declarations */ static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); +static void PIOS_RFM22B_Task(void *parameters); static void rfm22_processInt(void); static void rfm22_setTxMode(uint8_t mode); @@ -509,6 +519,14 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22_getTxPower()); + // Register the watchdog timer for the radio driver task +#ifdef PIOS_WDG_RFM22B + PIOS_WDG_RegisterFlag(PIOS_WDG_RFM22B); +#endif /* PIOS_WDG_RFM22B */ + + // Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler. + xTaskCreate(PIOS_RFM22B_Task, (signed char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void*)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle)); + // Setup a real-time clock callback to kickstart the radio if a transfer lock sup. if (!PIOS_RTC_RegisterTickCallback(PIOS_RFM22B_Supervisor, *rfm22b_id)) { PIOS_DEBUG_Assert(0); @@ -545,6 +563,30 @@ static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) } +/** + * The task that controls the radio state machine. + */ +static void PIOS_RFM22B_Task(void *parameters) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters; + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + + while(1) + { +#ifdef PIOS_WDG_RFM22B + // Update the watchdog timer + //PIOS_WDG_UpdateFlag(PIOS_WDG_RFM22B); +#endif /* PIOS_WDG_RFM22B */ + + // Process any pending interrrupt + if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { + rfm22b_dev->rfm32_irqs_processed++; + rfm22_processInt(); + } + } +} + static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) { struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; @@ -767,9 +809,6 @@ static uint8_t rfm22_read_noclaim(uint8_t addr) // ************************************ // external interrupt -uint32_t rfm32_errors; -uint32_t rfm32_irqs_processed; - void PIOS_RFM22_EXT_Int(void) { bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); @@ -779,23 +818,12 @@ void PIOS_RFM22_EXT_Int(void) if (!exec_using_spi) { if (xSemaphoreGiveFromISR(g_rfm22b_dev->isrPending, &pxHigherPriorityTaskWoken) != pdTRUE) { // Something went fairly seriously wrong - rfm32_errors++; + g_rfm22b_dev->rfm32_errors++; } portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); } } -void PIOS_RFM22_processPendingISR(uint32_t wait_ms) -{ - bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); - PIOS_Assert(valid); - - if ( xSemaphoreTake(g_rfm22b_dev->isrPending, wait_ms / portTICK_RATE_MS) == pdTRUE ) { - rfm32_irqs_processed++; - rfm22_processInt(); - } -} - // ************************************ // set/get the current tx power setting From 8ca2e85f4c65d3272c54a2b7b73d208c0b3491ee Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Wed, 12 Sep 2012 18:24:19 -0700 Subject: [PATCH 464/508] RFM22B: Removed incorrect defaulting of tx power level. --- flight/PiOS/Common/pios_rfm22b.c | 76 +++++++++++++------------------- flight/PiOS/inc/pios_rfm22b.h | 1 + 2 files changed, 31 insertions(+), 46 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 6029d8488..af15b8cc4 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -96,18 +96,6 @@ #define SYNC_BYTE_3 0x4B // #define SYNC_BYTE_4 0x59 // -// ************************************ -// the default TX power level - -#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_0 // +1dBm ... 1.25mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_1 // +2dBm ... 1.6mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_2 // +5dBm ... 3.16mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_3 // +8dBm ... 6.3mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_4 // +11dBm .. 12.6mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_5 // +14dBm .. 25mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_6 // +17dBm .. 50mW -//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_7 // +20dBm .. 100mW - // ************************************ // the default RF datarate @@ -181,6 +169,9 @@ struct pios_rfm22b_dev { uint16_t supv_timer; uint16_t resets; + // the transmit power to use for data transmissions + uint8_t tx_power; + // Stats uint32_t rfm32_errors; uint32_t rfm32_irqs_processed; @@ -345,8 +336,6 @@ volatile uint8_t osc_load_cap; // xtal frequency calibration value volatile uint8_t rssi; // the current RSSI (register value) volatile int8_t rssi_dBm; // dBm value -// the transmit power to use for data transmissions -uint8_t tx_power; // the tx power register read back volatile uint8_t tx_pwr; @@ -456,6 +445,9 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Initialize the TX pre-buffer pointer. tx_pre_buffer_size = 0; + // Initialize the max tx power level. + PIOS_RFM22B_SetTxPower(*rfm22b_id, cfg->maxTxPower); + // Create our (hopefully) unique 32 bit id from the processor serial number. uint8_t crcs[] = { 0, 0, 0, 0 }; { @@ -511,13 +503,12 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu rfm22_setFreqCalibration(cfg->RFXtalCap); rfm22_setNominalCarrierFrequency(cfg->frequencyHz); rfm22_setDatarate(cfg->maxRFBandwidth, true); - rfm22_setTxPower(cfg->maxTxPower); DEBUG_PRINTF(2, "\n\r"); DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate()); DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); - DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22_getTxPower()); + DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22b_dev->tx_power); // Register the watchdog timer for the radio driver task #ifdef PIOS_WDG_RFM22B @@ -542,6 +533,26 @@ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) return rfm22b_dev->deviceID; } +void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + bool valid = PIOS_RFM22B_validate(rfm22b_dev); + PIOS_Assert(valid); + + switch (tx_pwr) + { + case 0: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW + case 1: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW + case 2: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW + case 3: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW + case 4: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW + case 5: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW + case 6: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW + case 7: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW + default: break; + } +} + int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) { return rfm22_receivedRSSI(); @@ -824,30 +835,6 @@ void PIOS_RFM22_EXT_Int(void) } } -// ************************************ -// set/get the current tx power setting - -void rfm22_setTxPower(uint8_t tx_pwr) -{ - switch (tx_pwr) - { - case 0: tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW - case 1: tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW - case 2: tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW - case 3: tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW - case 4: tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW - case 5: tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW - case 6: tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW - case 7: tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW - default: break; - } -} - -uint8_t rfm22_getTxPower(void) -{ - return tx_power; -} - // ************************************ uint32_t rfm22_minFrequency(void) @@ -1238,7 +1225,7 @@ uint8_t rfm22_txStart() // set the tx power rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | - RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); + RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power); // clear FIFOs rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); @@ -1301,7 +1288,7 @@ static void rfm22_setTxMode(uint8_t mode) // Set the tx power rfm22_write_noclaim(RFM22_tx_power,RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | - RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); + RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power); uint8_t fd_bit = rfm22_read_noclaim(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; if (mode == TX_CARRIER_MODE) @@ -1933,9 +1920,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq temperature_reg = 0; - // set the TX power - tx_power = RFM22_DEFAULT_RF_POWER; - tx_pwr = 0; // **************** @@ -2123,7 +2107,7 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ // set the tx power rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | - RFM22_tx_pwr_lna_sw | tx_power); + RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power); // TX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 176b25710..0cc685da3 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -49,6 +49,7 @@ struct pios_rfm22b_cfg { /* Public Functions */ extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg); +extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); From 057227726b733fabb236dbc5cd2e28ae98f85b0a Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Wed, 12 Sep 2012 19:19:38 -0700 Subject: [PATCH 465/508] Radio: Make sure pios_packet_handler is set to 0 when radio module is not initialized. --- flight/Modules/Radio/radio.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 65650d815..7b61dce34 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -166,8 +166,10 @@ static int32_t RadioInitialize(void) HwSettingsInitialize(); uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; HwSettingsOptionalModulesGet(optionalModules); - if (optionalModules[HWSETTINGS_OPTIONALMODULES_RADIO] != HWSETTINGS_OPTIONALMODULES_ENABLED) + if (optionalModules[HWSETTINGS_OPTIONALMODULES_RADIO] != HWSETTINGS_OPTIONALMODULES_ENABLED) { + pios_packet_handler = 0; return -1; + } #endif // Initalize out UAVOs From 80509d264e215886450830181c34ef51b9e557e3 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Fri, 14 Sep 2012 19:30:02 -0700 Subject: [PATCH 466/508] RFM22B: Start at cleaning up the processing interrupt handling, and starting to make it more of a state machine. Also removed the supervisor, which was causing unnecessary resets. The supervisor functionality is not in the the driver thread. --- flight/PiOS/Common/pios_rfm22b.c | 604 +++++++++-------------------- flight/PiOS/inc/pios_rfm22b_priv.h | 13 - 2 files changed, 182 insertions(+), 435 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index af15b8cc4..cca0a3b9b 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -63,7 +63,7 @@ // RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). // A 256 byte message at 56kbps should take less than 40ms // Note: This timeout should be rate dependent. -#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 65 // ~100ms +#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms // this is too adjust the RF module so that it is on frequency #define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default @@ -144,6 +144,24 @@ enum pios_rfm22b_dev_magic { PIOS_RFM22B_DEV_MAGIC = 0x68e971b6, }; +enum pios_rfm22b_state { + RFM22B_STATE_INITIALIZING, + RFM22B_STATE_RESETTING, + RFM22B_STATE_ERROR, + RFM22B_STATE_RX_WAIT_PREAMBLE, + RFM22B_STATE_RX_WAIT_SYNC, + RFM22B_STATE_RX_DATA, + RFM22B_STATE_RX_COMPLETE, + RFM22B_STATE_TX_START, + RFM22B_STATE_TX_DATA, + RFM22B_STATE_TX_COMPLETE +}; + +enum pios_rfm22b_event { + RFM22B_EVENT_NONE, + RFM22B_EVENT_INT_RECEIVED +}; + struct pios_rfm22b_dev { enum pios_rfm22b_dev_magic magic; struct pios_rfm22b_cfg cfg; @@ -165,19 +183,18 @@ struct pios_rfm22b_dev { pios_com_callback tx_out_cb; uint32_t tx_out_context; - // The supervisor countdown timer. - uint16_t supv_timer; - uint16_t resets; - // the transmit power to use for data transmissions uint8_t tx_power; - // Stats - uint32_t rfm32_errors; - uint32_t rfm32_irqs_processed; -}; + // The state machine state and the current event + enum pios_rfm22b_state state; + enum pios_rfm22b_event event; -uint32_t random32 = 0x459ab8d8; + // Stats + uint16_t resets; + uint32_t errors; + uint32_t irqs_processed; +}; // Must ensure these prefilled arrays match the define sizes static const uint8_t FULL_PREAMBLE[FIFO_SIZE] = @@ -205,10 +222,10 @@ static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF}; /* Local function forwared declarations */ -static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); static void PIOS_RFM22B_Task(void *parameters); -static void rfm22_processInt(void); -static void rfm22_setTxMode(uint8_t mode); +static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state); +static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR); +static void rfm22_processInt(struct pios_rfm22b_dev *rfm22b_dev); // SPI read/write functions static void rfm22_write(uint8_t addr, uint8_t data); @@ -301,8 +318,6 @@ volatile bool exec_using_spi; // set this if you want to access the SPI uint8_t device_type; // the RF chips device ID number uint8_t device_version; // the RF chips revision number -volatile uint8_t rf_mode; // holds our current RF mode - uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use uint32_t carrier_frequency_hz; // the current RF frequency we are on @@ -366,8 +381,6 @@ volatile int8_t rx_packet_afc_Hz; // the receive packet frequency offset int lookup_index; int ss_lookup_index; -volatile bool power_on_reset; // set if the RF module has reset itself - volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding. volatile uint16_t rfm22_int_time_outs; // counter volatile uint16_t prev_rfm22_int_time_outs; // @@ -376,8 +389,6 @@ uint16_t timeout_ms = 20000; // uint16_t timeout_sync_ms = 3; // uint16_t timeout_data_ms = 20; // -struct pios_rfm22b_dev * rfm22b_dev_g; - static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev) { @@ -392,7 +403,6 @@ static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void) rfm22b_dev = (struct pios_rfm22b_dev *)pvPortMalloc(sizeof(*rfm22b_dev)); rfm22b_dev->spi_id = 0; if (!rfm22b_dev) return(NULL); - rfm22b_dev_g = rfm22b_dev; rfm22b_dev->magic = PIOS_RFM22B_DEV_MAGIC; return(rfm22b_dev); @@ -433,6 +443,15 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu rfm22b_dev->slave_num = slave_num; rfm22b_dev->spi_id = spi_id; + // Set the state to initializing. + rfm22b_dev->state = RFM22B_STATE_INITIALIZING; + rfm22b_dev->event = RFM22B_EVENT_NONE; + + // Initialize the stats. + rfm22b_dev->resets = 0; + rfm22b_dev->errors = 0; + rfm22b_dev->irqs_processed = 0; + // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; @@ -460,10 +479,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24; DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); - // Initialize the supervisor timer. - rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; - rfm22b_dev->resets = 0; - // Initialize the external interrupt. PIOS_EXTI_Init(cfg->exti_cfg); @@ -518,26 +533,70 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler. xTaskCreate(PIOS_RFM22B_Task, (signed char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void*)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle)); - // Setup a real-time clock callback to kickstart the radio if a transfer lock sup. - if (!PIOS_RTC_RegisterTickCallback(PIOS_RFM22B_Supervisor, *rfm22b_id)) { - PIOS_DEBUG_Assert(0); - } - return(0); } +/** + * The RFM22B external interrupt routine. + */ +void PIOS_RFM22_EXT_Int(void) +{ + if (!PIOS_RFM22B_validate(g_rfm22b_dev)) + return; + + // Inject an interrupt event into the state machine. + PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_INT_RECEIVED, true); +} + +/** + * Inject an event into the RFM22B state machine. + * \param[in] rfm22b_dev The device structure + * \param[in] event The event to inject + * \param[in] inISR Is this being called from an interrrup service routine? + */ +static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR) +{ + + // Store the event. + rfm22b_dev->event = event; + + // Signal the semaphore to wake up the handler thread. + if (inISR) { + portBASE_TYPE pxHigherPriorityTaskWoken; + if (xSemaphoreGiveFromISR(rfm22b_dev->isrPending, &pxHigherPriorityTaskWoken) != pdTRUE) { + // Something went fairly seriously wrong + rfm22b_dev->errors++; + } + portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); + } + else + { + if (xSemaphoreGive(rfm22b_dev->isrPending) != pdTRUE) { + // Something went fairly seriously wrong + rfm22b_dev->errors++; + } + } +} + +/** + * Returns the unique device ID for th RFM22B device. + * \param[in] rfm22b_id The RFM22B device index. + * \return The unique device ID + */ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; - - return rfm22b_dev->deviceID; + if(PIOS_RFM22B_validate(rfm22b_dev)) + return rfm22b_dev->deviceID; + else + return 0; } void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; - bool valid = PIOS_RFM22B_validate(rfm22b_dev); - PIOS_Assert(valid); + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return; switch (tx_pwr) { @@ -580,20 +639,46 @@ static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) static void PIOS_RFM22B_Task(void *parameters) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters; - bool valid = PIOS_RFM22B_validate(rfm22b_dev); - PIOS_Assert(valid); + if (!PIOS_RFM22B_validate(rfm22b_dev)) + return; + static portTickType lastEventTime; while(1) { #ifdef PIOS_WDG_RFM22B // Update the watchdog timer - //PIOS_WDG_UpdateFlag(PIOS_WDG_RFM22B); + PIOS_WDG_UpdateFlag(PIOS_WDG_RFM22B); #endif /* PIOS_WDG_RFM22B */ - // Process any pending interrrupt + // Wait for a signal indicating an external interrupt or a pending send/receive request. if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { - rfm22b_dev->rfm32_irqs_processed++; - rfm22_processInt(); + rfm22b_dev->irqs_processed++; + lastEventTime = xTaskGetTickCount(); + rfm22_processInt(rfm22b_dev); + } + else + { + // Has it been too long since the last event? + portTickType timeSinceEvent = xTaskGetTickCount() - lastEventTime; + if ((timeSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) + { + rfm22b_dev->resets++; + TX_LED_OFF; + TX_LED_OFF; + + /* Clear the TX buffer in case we locked up in a transmit */ + tx_data_wr = 0; + + rfm22_init_normal(rfm22b_dev->deviceID, rfm22b_dev->cfg.minFrequencyHz, rfm22b_dev->cfg.maxFrequencyHz, 50000); + + /* Start a packet transfer if one is available. */ + rfm22b_dev->state = RFM22B_STATE_RX_WAIT_PREAMBLE; + if(rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE) + { + /* Switch to RX mode */ + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); + } + } } } } @@ -616,9 +701,8 @@ static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) if (tx_data_wr > 0) return; - // we are currently transmitting or scanning the spectrum - if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || - rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM) + // we are currently transmitting? + if (rfm22b_dev->state == RFM22B_STATE_TX_DATA) return; // is the channel clear to transmit on? @@ -674,47 +758,6 @@ static void PIOS_RFM22B_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback rfm22b_dev->tx_out_cb = tx_out_cb; } -static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id) -{ - /* Recover our device context */ - struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; - - if (!PIOS_RFM22B_validate(rfm22b_dev)) { - /* Invalid device specified */ - return; - } - - /* If we're waiting for a receive, we just need to make sure that there are no packets waiting to be transmitted. */ - if(rf_mode == RX_WAIT_PREAMBLE_MODE) - { - /* Start a packet transfer if one is available. */ - PIOS_RFM22B_TxStart(rfm22b_id, 0); - return; - } - - /* The radio must be locked up if the timer reaches 0 */ - if(--(rfm22b_dev->supv_timer) != 0) - return; - ++(rfm22b_dev->resets); - - TX_LED_OFF; - TX_LED_OFF; - - /* Clear the TX buffer in case we locked up in a transmit */ - tx_data_wr = 0; - - rfm22_init_normal(rfm22b_dev->deviceID, rfm22b_dev->cfg.minFrequencyHz, rfm22b_dev->cfg.maxFrequencyHz, 50000); - - /* Start a packet transfer if one is available. */ - rf_mode = RX_WAIT_PREAMBLE_MODE; - PIOS_RFM22B_TxStart(rfm22b_id, 0); - if(rf_mode == RX_WAIT_PREAMBLE_MODE) - { - /* Switch to RX mode */ - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - } -} - // ************************************ // SPI read/write @@ -769,7 +812,6 @@ static void rfm22_write(uint8_t addr, uint8_t data) * toggle the NSS line * @param[in] addr The address of the RFM22b register to write * @param[in] data The data to write to that register - */ static void rfm22_write_noclaim(uint8_t addr, uint8_t data) { uint8_t buf[2] = {addr | 0x80, data}; @@ -779,6 +821,7 @@ static void rfm22_write_noclaim(uint8_t addr, uint8_t data) rfm22_deassertCs(); } } +*/ /** @@ -809,7 +852,7 @@ static uint8_t rfm22_read_noclaim(uint8_t addr) { uint8_t out[2] = {addr & 0x7F, 0xFF}; uint8_t in[2]; - if (PIOS_RFM22B_validate(rfm22b_dev_g)) { + if (PIOS_RFM22B_validate(g_rfm22b_dev)) { rfm22_assertCs(); PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out, in, sizeof(out), NULL); rfm22_deassertCs(); @@ -817,24 +860,6 @@ static uint8_t rfm22_read_noclaim(uint8_t addr) return in[1]; } -// ************************************ -// external interrupt - -void PIOS_RFM22_EXT_Int(void) -{ - bool valid = PIOS_RFM22B_validate(g_rfm22b_dev); - PIOS_Assert(valid); - - portBASE_TYPE pxHigherPriorityTaskWoken; - if (!exec_using_spi) { - if (xSemaphoreGiveFromISR(g_rfm22b_dev->isrPending, &pxHigherPriorityTaskWoken) != pdTRUE) { - // Something went fairly seriously wrong - g_rfm22b_dev->rfm32_errors++; - } - portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); - } -} - // ************************************ uint32_t rfm22_minFrequency(void) @@ -1082,51 +1107,7 @@ uint32_t rfm22_getDatarate(void) // ************************************ -void rfm22_setSSBandwidth(uint32_t bandwidth_index) -{ - - exec_using_spi = true; - - ss_lookup_index = bandwidth_index; - - ss_rf_bandwidth_used = ss_rx_bandwidth[lookup_index]; - - // ******************************** - - rfm22_write(0x1C, ss_reg_1C[ss_lookup_index]); // rfm22_if_filter_bandwidth - rfm22_write(0x1D, ss_reg_1D[ss_lookup_index]); // rfm22_afc_loop_gearshift_override - - rfm22_write(0x20, ss_reg_20[ss_lookup_index]); // rfm22_clk_recovery_oversampling_ratio - rfm22_write(0x21, ss_reg_21[ss_lookup_index]); // rfm22_clk_recovery_offset2 - rfm22_write(0x22, ss_reg_22[ss_lookup_index]); // rfm22_clk_recovery_offset1 - rfm22_write(0x23, ss_reg_23[ss_lookup_index]); // rfm22_clk_recovery_offset0 - rfm22_write(0x24, ss_reg_24[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain1 - rfm22_write(0x25, ss_reg_25[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain0 - - rfm22_write(0x2A, ss_reg_2A[ss_lookup_index]); // rfm22_afc_limiter - - rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override - - rfm22_write(0x70, ss_reg_70[ss_lookup_index]); // rfm22_modulation_mode_control1 - rfm22_write(0x71, ss_reg_71[ss_lookup_index]); // rfm22_modulation_mode_control2 - - rfm22_write(RFM22_ook_counter_value1, 0x00); - rfm22_write(RFM22_ook_counter_value2, 0x00); - - // ******************************** - -#if defined(RFM22_DEBUG) - DEBUG_PRINTF(2, "ss_rf_rx_bandwidth[%u]: %u\n\r", ss_lookup_index, ss_rx_bandwidth[ss_lookup_index]); -#endif - - // ******* - - exec_using_spi = false; -} - -// ************************************ - -void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) +static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state) { exec_using_spi = true; @@ -1140,33 +1121,18 @@ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode) RX_LED_OFF; TX_LED_OFF; - if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - { - // FIFO mode, GFSK modulation - uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | - RFM22_mmc2_modtyp_gfsk); - } - // empty the rx buffer rx_buffer_wr = 0; // reset the timer rfm22_int_timer = 0; - rf_mode = mode; + g_rfm22b_dev->state = state; // Clear the TX buffer. tx_data_rd = tx_data_wr = 0; // clear FIFOs - if (!multi_packet_mode) - { - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, 0x00); - } else { - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk | RFM22_opfc2_ffclrrx | - RFM22_opfc2_ffclrtx); - rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk); - } + rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); + rfm22_write(RFM22_op_and_func_ctrl2, 0x00); // enable RX interrupts rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid | @@ -1193,9 +1159,6 @@ uint8_t rfm22_txStart() exec_using_spi = true; - // Initialize the supervisor timer. - rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; - // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); rfm22_write(RFM22_interrupt_enable2, 0x00); @@ -1253,7 +1216,7 @@ uint8_t rfm22_txStart() // reset the timer rfm22_int_timer = 0; - rf_mode = TX_DATA_MODE; + g_rfm22b_dev->state = RFM22B_STATE_TX_DATA; // enable TX interrupts rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); @@ -1267,104 +1230,10 @@ uint8_t rfm22_txStart() return 1; } - -static void rfm22_setTxMode(uint8_t mode) -{ - if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE) - return; // invalid mode - - rfm22_claimBus(); - rfm22_assertCs(); - - // Disaable interrupts (IE1, IE2 = 0) - uint8_t out_buf[3] = {RFM22_interrupt_enable1 | 0x80, 0x00, 0x00}; - PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out_buf, NULL, sizeof(out_buf), NULL); - rfm22_deassertCs(); - - // TUNE mode - rfm22_write_noclaim(RFM22_op_and_func_ctrl1,RFM22_opfc1_pllon); - - RX_LED_OFF; - - // Set the tx power - rfm22_write_noclaim(RFM22_tx_power,RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 | - RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power); - - uint8_t fd_bit = rfm22_read_noclaim(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; - if (mode == TX_CARRIER_MODE) - // blank carrier mode - for testing - rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | - RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier - else if (mode == TX_PN_MODE) - // psuedo random data carrier mode - for testing - rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | - RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier - else - // data transmission - // FIFO mode, GFSK modulation - rfm22_write_noclaim(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | - RFM22_mmc2_modtyp_gfsk); - - // clear FIFOs - rfm22_write_noclaim(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); - rfm22_write_noclaim(RFM22_op_and_func_ctrl2, 0x00); - - // add some data to the chips TX FIFO before enabling the transmitter - { - uint16_t rd = 0; - uint16_t wr = tx_data_wr; - - if (mode == TX_DATA_MODE) - // set the total number of data bytes we are going to transmit - rfm22_write_noclaim(RFM22_transmit_packet_length, wr); - - uint16_t i = 0; - rfm22_assertCs(); - PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, 0x80 | RFM22_fifo_access); // Initiate burst write - if (mode == TX_STREAM_MODE) { - if (rd >= wr) - i += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, FULL_PREAMBLE, NULL, sizeof(FULL_PREAMBLE), NULL); - else // add the RF heaader - i += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, HEADER, NULL, sizeof(HEADER), NULL); - } - - // Send data if there is any and there is space in the buffer available - // Bytes available to send minus how many we have sent - int32_t bytes_to_send = wr - rd; - bytes_to_send = ((bytes_to_send + i)> FIFO_SIZE) ? (FIFO_SIZE - i) : bytes_to_send; - if (bytes_to_send > 0) - rd += PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rd], NULL, bytes_to_send, NULL); - - rfm22_deassertCs(); - - tx_data_rd = rd; - } - - // reset the timer - rfm22_int_timer = 0; - - rf_mode = mode; - - // enable TX interrupts - // rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr); - rfm22_write_noclaim(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); - - // read interrupt status - clear interrupts - rfm22_read_noclaim(RFM22_interrupt_status1); - rfm22_read_noclaim(RFM22_interrupt_status2); - - // enable the transmitter - // rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon); - rfm22_write_noclaim(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon); - - rfm22_releaseBus(); - TX_LED_ON; -} - // ************************************ // external interrupt line triggered (or polled) from the rf chip -void rfm22_processRxInt(void) +void rfm22_processRxInt(struct pios_rfm22b_dev *rfm22b_dev) { register uint8_t int_stat1 = int_status1; register uint8_t int_stat2 = int_status2; @@ -1372,21 +1241,21 @@ void rfm22_processRxInt(void) // FIFO under/over flow error. Restart RX mode. if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } // Valid preamble detected - if (int_stat2 & RFM22_is2_ipreaval && (rf_mode == RX_WAIT_PREAMBLE_MODE)) + if (int_stat2 & RFM22_is2_ipreaval && (rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE)) { - rf_mode = RX_WAIT_SYNC_MODE; + rfm22b_dev->state = RFM22B_STATE_RX_WAIT_SYNC; RX_LED_ON; } // Sync word detected - if (int_stat2 & RFM22_is2_iswdet && ((rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE))) + if (int_stat2 & RFM22_is2_iswdet && ((rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE || rfm22b_dev->state == RFM22B_STATE_RX_WAIT_SYNC))) { - rf_mode = RX_DATA_MODE; + rfm22b_dev->state = RFM22B_STATE_RX_DATA; RX_LED_ON; // read the 10-bit signed afc correction value @@ -1407,7 +1276,7 @@ void rfm22_processRxInt(void) // RX FIFO almost full, it needs emptying if (int_stat1 & RFM22_is1_irxffafull) { - if (rf_mode == RX_DATA_MODE) + if (rfm22b_dev->state == RFM22B_STATE_RX_DATA) { // read data from the rf chips FIFO buffer // read the total length of the packet data @@ -1416,22 +1285,22 @@ void rfm22_processRxInt(void) // The received packet is going to be larger than the specified length if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } // Another packet length error. if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid)) { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } // Fetch the data from the RX FIFO rfm22_claimBus(); rfm22_assertCs(); - PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); - rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF, + PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); + rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, (uint8_t *) &rx_buffer[rx_buffer_wr],RX_FIFO_HI_WATERMARK,NULL) == 0) ? RX_FIFO_HI_WATERMARK : 0; rfm22_deassertCs(); @@ -1440,8 +1309,8 @@ void rfm22_processRxInt(void) // Clear the RX FIFO rfm22_claimBus(); rfm22_assertCs(); - PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); - PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF,NULL,RX_FIFO_HI_WATERMARK,NULL); + PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); + PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF,NULL,RX_FIFO_HI_WATERMARK,NULL); rfm22_deassertCs(); rfm22_releaseBus(); } @@ -1451,7 +1320,7 @@ void rfm22_processRxInt(void) if (int_stat1 & RFM22_is1_icrerror) { rfm22_int_timer = 0; // reset the timer - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } @@ -1469,8 +1338,8 @@ void rfm22_processRxInt(void) // Fetch the data from the RX FIFO rfm22_claimBus(); rfm22_assertCs(); - PIOS_SPI_TransferByte(rfm22b_dev_g->spi_id,RFM22_fifo_access & 0x7F); - rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev_g->spi_id,OUT_FF, + PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); + rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, (uint8_t *) &rx_buffer[rx_buffer_wr],bytes_to_read,NULL) == 0) ? bytes_to_read : 0; rfm22_deassertCs(); @@ -1480,7 +1349,7 @@ void rfm22_processRxInt(void) if (rx_buffer_wr != len) { // we have a packet length error .. discard the packet - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } @@ -1497,9 +1366,9 @@ void rfm22_processRxInt(void) rx_buffer[rx_buffer_wr++] = rx_packet_start_afc_Hz; // Pass this packet on bool need_yield = false; - if (rfm22b_dev_g->rx_in_cb) - (rfm22b_dev_g->rx_in_cb)(rfm22b_dev_g->rx_in_context, (uint8_t*)rx_buffer, - rx_buffer_wr, NULL, &need_yield); + if (rfm22b_dev->rx_in_cb) + (rfm22b_dev->rx_in_cb)(rfm22b_dev->rx_in_context, (uint8_t*)rx_buffer, + rx_buffer_wr, NULL, &need_yield); rx_buffer_wr = 0; } @@ -1507,13 +1376,13 @@ void rfm22_processRxInt(void) if(!rfm22_txStart()) { // Switch to RX mode - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); } } } -void rfm22_processTxInt(void) +void rfm22_processTxInt(struct pios_rfm22b_dev *rfm22b_dev) { register uint8_t int_stat1 = int_status1; @@ -1523,7 +1392,7 @@ void rfm22_processTxInt(void) // FIFO under/over flow error. Back to RX mode. if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } @@ -1531,7 +1400,7 @@ void rfm22_processTxInt(void) if (rfm22_int_timer >= timeout_data_ms) { rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } @@ -1541,7 +1410,7 @@ void rfm22_processTxInt(void) if (rfm22_int_timer >= 100) { rfm22_int_time_outs++; - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); // back to rx mode return; } } @@ -1570,30 +1439,27 @@ void rfm22_processTxInt(void) if(!rfm22_txStart()) { // Switch to RX mode - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); return; } } } -static void rfm22_processInt(void) +static void rfm22_processInt(struct pios_rfm22b_dev *rfm22b_dev) { // we haven't yet been initialized - if (!initialized || power_on_reset || !PIOS_RFM22B_validate(rfm22b_dev_g)) + if (!PIOS_RFM22B_validate(rfm22b_dev)) return; exec_using_spi = true; - // Reset the supervisor timer. - rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT; - // 1. Read the interrupt statuses with burst read rfm22_claimBus(); // Set RC and the semaphore uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF}; uint8_t read_buf[3]; rfm22_assertCs(); - PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL); + PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL); rfm22_deassertCs(); int_status1 = read_buf[1]; int_status2 = read_buf[2]; @@ -1608,8 +1474,7 @@ static void rfm22_processInt(void) rfm22_releaseBus(); // Read the RSSI if we're in RX mode - if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && - rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE) + if (rfm22b_dev->state != RFM22B_STATE_TX_DATA) { // read rx signal strength .. 45 = -100dBm, 205 = -20dBm rssi = rfm22_read(RFM22_rssi); @@ -1623,44 +1488,28 @@ static void rfm22_processInt(void) // the RF module has gone and done a reset - we need to re-initialize the rf module if (int_status2 & RFM22_is2_ipor) { - initialized = false; - power_on_reset = true; + rfm22b_dev->state = RFM22B_STATE_RESETTING; // Need to do something here! return; } - switch (rf_mode) + switch (rfm22b_dev->state) { - case RX_SCAN_SPECTRUM: + case RFM22B_STATE_RX_WAIT_PREAMBLE: + case RFM22B_STATE_RX_WAIT_SYNC: + case RFM22B_STATE_RX_DATA: + + rfm22_processRxInt(rfm22b_dev); break; - case RX_WAIT_PREAMBLE_MODE: - case RX_WAIT_SYNC_MODE: - case RX_DATA_MODE: - - rfm22_processRxInt(); - break; - - case TX_DATA_MODE: - case TX_STREAM_MODE: - - rfm22_processTxInt(); - break; - - case TX_CARRIER_MODE: - case TX_PN_MODE: - - // if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit - // { - // rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode - // tx_data_rd = tx_data_wr = 0; // wipe TX buffer - // break; - // } + case RFM22B_STATE_TX_DATA: + rfm22_processTxInt(rfm22b_dev); break; default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode + // to rx mode + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); break; } @@ -1698,70 +1547,16 @@ int32_t rfm22_receivedAFCHz(void) // ************************************ -// ************************************ - -void rfm22_setTxStream(void) // TEST ONLY -{ - if (!initialized) - return; - - tx_data_rd = tx_data_wr = 0; - - rfm22_setTxMode(TX_STREAM_MODE); -} - -// ************************************ - -void rfm22_setTxNormal(void) -{ - if (!initialized) - return; - - // if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - if (rf_mode != RX_SCAN_SPECTRUM) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - tx_data_rd = tx_data_wr = 0; - - rx_packet_start_rssi_dBm = 0; - rx_packet_start_afc_Hz = 0; - rx_packet_rssi_dBm = 0; - rx_packet_afc_Hz = 0; - } -} - -// enable a blank tx carrier (for frequency alignment) -void rfm22_setTxCarrierMode(void) -{ - if (!initialized) - return; - - if (rf_mode != TX_CARRIER_MODE && rf_mode != RX_SCAN_SPECTRUM) - rfm22_setTxMode(TX_CARRIER_MODE); -} - -// enable a psuedo random data tx carrier (for spectrum inspection) -void rfm22_setTxPNMode(void) -{ - if (!initialized) - return; - - if (rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM) - rfm22_setTxMode(TX_PN_MODE); -} - -// ************************************ - // return the current mode int8_t rfm22_currentMode(void) { - return rf_mode; + return g_rfm22b_dev->state; } // return true if we are transmitting bool rfm22_transmitting(void) { - return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE); + return (g_rfm22b_dev->state == RFM22B_STATE_TX_DATA); } // return true if the channel is clear to transmit on @@ -1771,7 +1566,7 @@ bool rfm22_channelIsClear(void) // we haven't yet been initialized return false; - if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE) + if (g_rfm22b_dev->state != RFM22B_STATE_RX_WAIT_PREAMBLE && g_rfm22b_dev->state != RFM22B_STATE_RX_WAIT_SYNC) // we are receiving something or we are transmitting or we are scanning the spectrum return false; @@ -1781,13 +1576,7 @@ bool rfm22_channelIsClear(void) // return true if the transmiter is ready for use bool rfm22_txReady(void) { - if (!initialized) - // we haven't yet been initialized - return false; - - return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && - rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE && - rf_mode != RX_SCAN_SPECTRUM); + return (tx_data_rd == 0 && tx_data_wr == 0 && g_rfm22b_dev->state != RFM22B_STATE_TX_DATA); } // ************************************ @@ -1797,25 +1586,11 @@ void rfm22_setFreqCalibration(uint8_t value) { osc_load_cap = value; - if (!initialized || power_on_reset) - return; // we haven't yet been initialized - - uint8_t prev_rf_mode = rf_mode; - - if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE) - { - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); - tx_data_rd = tx_data_wr = 0; - } - exec_using_spi = true; rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); exec_using_spi = false; - - if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE) - rfm22_setTxMode(prev_rf_mode); } uint8_t rfm22_getFreqCalibration(void) @@ -1823,19 +1598,6 @@ uint8_t rfm22_getFreqCalibration(void) return osc_load_cap; } -// ************************************ -// can be called from an interrupt if you wish - -void rfm22_1ms_tick(void) -{ // call this once every ms - if (!initialized) return; // we haven't yet been initialized - - if (rf_mode != RX_SCAN_SPECTRUM) - { - if (rfm22_int_timer < 0xffff) rfm22_int_timer++; - } -} - // ************************************ // reset the RF module @@ -1843,8 +1605,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq { initialized = false; - power_on_reset = false; - // **************** exec_using_spi = true; @@ -1886,7 +1646,7 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // **************** - rf_mode = mode; + g_rfm22b_dev->state = mode; device_status = int_status1 = int_status2 = ezmac_status = 0; @@ -1992,7 +1752,7 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // choose the 3 GPIO pin functions rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value - if (rfm22b_dev_g->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { + if (g_rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) } else { @@ -2011,7 +1771,7 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size) { - int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz); + int res = rfm22_resetModule(RFM22B_STATE_RX_WAIT_PREAMBLE, min_frequency_hz, max_frequency_hz); if (res < 0) return res; @@ -2118,7 +1878,7 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ // RX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); - rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); + PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); initialized = true; diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 4535a472e..ce6bf96f5 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -50,17 +50,6 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; // ************************************ -enum { RX_SCAN_SPECTRUM = 0, - RX_WAIT_PREAMBLE_MODE, - RX_WAIT_SYNC_MODE, - RX_DATA_MODE, - TX_DATA_MODE, - TX_STREAM_MODE, - TX_CARRIER_MODE, - TX_PN_MODE}; - -// ************************************ - #define BIT0 (1u << 0) #define BIT1 (1u << 1) #define BIT2 (1u << 2) @@ -609,8 +598,6 @@ uint32_t rfm22_freqHopSize(void); void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening); uint32_t rfm22_getDatarate(void); -void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode); - int8_t rfm22_getRSSI(void); int8_t rfm22_receivedRSSI(void); From 61200f01f5707815da82f1be29e4bd985f0be833 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sun, 16 Sep 2012 19:33:30 -0700 Subject: [PATCH 467/508] RFM22B: Major refactoring of te RFM22B driver to implement a state machine for the driver. The state machine should now be complete, and the driver seems to be working pretty well on both the RM and the pipx. --- flight/Libraries/packet_handler.c | 2 +- flight/PiOS/Common/pios_rfm22b.c | 840 ++++++++++++++++------------- flight/PiOS/inc/pios_rfm22b.h | 6 +- flight/PiOS/inc/pios_rfm22b_priv.h | 17 - 4 files changed, 461 insertions(+), 404 deletions(-) diff --git a/flight/Libraries/packet_handler.c b/flight/Libraries/packet_handler.c index c417371d7..9226c74ae 100644 --- a/flight/Libraries/packet_handler.c +++ b/flight/Libraries/packet_handler.c @@ -475,12 +475,12 @@ static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p) // Set the sequence ID to the current ID. p->header.tx_seq = data->tx_seq_id++; + p->header.source_id = data->cfg.source_id; // Add the error correcting code. encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); // Transmit the packet using the output stream. - p->header.source_id = data->cfg.source_id; if(data->output_stream(p) == -1) return 0; diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index cca0a3b9b..7a0e145dd 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -59,6 +59,8 @@ #define STACK_SIZE_BYTES 200 #define TASK_PRIORITY (tskIDLE_PRIORITY + 2) #define ISR_TIMEOUT 5 // ms +#define EVENT_QUEUE_SIZE 5 +#define PACKET_QUEUE_SIZE 3 // RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). // A 256 byte message at 56kbps should take less than 40ms @@ -145,21 +147,35 @@ enum pios_rfm22b_dev_magic { }; enum pios_rfm22b_state { + RFM22B_STATE_UNINITIALIZED, RFM22B_STATE_INITIALIZING, - RFM22B_STATE_RESETTING, RFM22B_STATE_ERROR, - RFM22B_STATE_RX_WAIT_PREAMBLE, - RFM22B_STATE_RX_WAIT_SYNC, + RFM22B_STATE_RX_MODE, + RFM22B_STATE_WAIT_PREAMBLE, + RFM22B_STATE_WAIT_SYNC, RFM22B_STATE_RX_DATA, - RFM22B_STATE_RX_COMPLETE, RFM22B_STATE_TX_START, RFM22B_STATE_TX_DATA, - RFM22B_STATE_TX_COMPLETE + RFM22B_STATE_FATAL_ERROR, + + RFM22B_STATE_NUM_STATES // Must be last }; enum pios_rfm22b_event { - RFM22B_EVENT_NONE, - RFM22B_EVENT_INT_RECEIVED + RFM22B_EVENT_INITIALIZE, + RFM22B_EVENT_INT_RECEIVED, + RFM22B_EVENT_TX_MODE, + RFM22B_EVENT_RX_MODE, + RFM22B_EVENT_PREAMBLE_DETECTED, + RFM22B_EVENT_SYNC_DETECTED, + RFM22B_EVENT_RX_COMPLETE, + RFM22B_EVENT_SEND_PACKET, + RFM22B_EVENT_TX_START, + RFM22B_EVENT_TX_COMPLETE, + RFM22B_EVENT_ERROR, + RFM22B_EVENT_FATAL_ERROR, + + RFM22B_EVENT_NUM_EVENTS // Must be last }; struct pios_rfm22b_dev { @@ -188,12 +204,34 @@ struct pios_rfm22b_dev { // The state machine state and the current event enum pios_rfm22b_state state; - enum pios_rfm22b_event event; + // The event queue handle + xQueueHandle eventQueue; + + // device status register + uint8_t device_status; + // interrupt status register 1 + uint8_t int_status1; + // interrupt status register 2 + uint8_t int_status2; + // ezmac status register + uint8_t ezmac_status; // Stats uint16_t resets; uint32_t errors; uint32_t irqs_processed; + // the current RSSI (register value) + uint8_t rssi; + // RSSI in dBm + int8_t rssi_dBm; + + // The packet queue handle + xQueueHandle packetQueue; +}; + +struct pios_rfm22b_transition { + enum pios_rfm22b_event (*entry_fn) (struct pios_rfm22b_dev *rfm22b_dev); + enum pios_rfm22b_state next_state[RFM22B_EVENT_NUM_EVENTS]; }; // Must ensure these prefilled arrays match the define sizes @@ -223,14 +261,27 @@ static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF, /* Local function forwared declarations */ static void PIOS_RFM22B_Task(void *parameters); -static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state); static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR); -static void rfm22_processInt(struct pios_rfm22b_dev *rfm22b_dev); +static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event); +static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev); +static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev); // SPI read/write functions +static void rfm22_assertCs(); +static void rfm22_deassertCs(); +static void rfm22_claimBus(); +static void rfm22_releaseBus(); static void rfm22_write(uint8_t addr, uint8_t data); static uint8_t rfm22_read(uint8_t addr); -uint8_t rfm22_txStart(); +static uint8_t rfm22_read_noclaim(uint8_t addr); /* Provide a COM driver */ static void PIOS_RFM22B_ChangeBaud(uint32_t rfm22b_id, uint32_t baud); @@ -248,6 +299,98 @@ const struct pios_com_driver pios_rfm22b_com_driver = { .bind_rx_cb = PIOS_RFM22B_RegisterRxCallback, }; +/* Te state transition table */ +const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_STATES] = { + [RFM22B_STATE_UNINITIALIZED] = { + .entry_fn = 0, + .next_state = { + [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + }, + }, + [RFM22B_STATE_INITIALIZING] = { + .entry_fn = rfm22_init, + .next_state = { + [RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_ERROR] = { + .entry_fn = rfm22_error, + .next_state = { + [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_RX_MODE] = { + .entry_fn = rfm22_setRxMode, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE, + [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_WAIT_PREAMBLE] = { + .entry_fn = rfm22_detectPreamble, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE, + [RFM22B_EVENT_PREAMBLE_DETECTED] = RFM22B_STATE_WAIT_SYNC, + [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_WAIT_SYNC] = { + .entry_fn = rfm22_detectSync, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_SYNC, + [RFM22B_EVENT_SYNC_DETECTED] = RFM22B_STATE_RX_DATA, + [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_RX_DATA] = { + .entry_fn = rfm22_rxData, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_RX_DATA, + [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, + [RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_TX_START] = { + .entry_fn = rfm22_txStart, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA, + [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, + [RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_TX_DATA] = { + .entry_fn = rfm22_txData, + .next_state = { + [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA, + [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, + [RFM22B_EVENT_TX_COMPLETE] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_FATAL_ERROR] = { + .entry_fn = rfm22_fatal_error, + .next_state = { + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, +}; + // xtal 10 ppm, 434MHz #define LOOKUP_SIZE 14 const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; @@ -336,11 +479,6 @@ uint8_t frequency_hop_step_size_reg; // uint8_t adc_config; // holds the adc config reg value -volatile uint8_t device_status; // device status register -volatile uint8_t int_status1; // interrupt status register 1 -volatile uint8_t int_status2; // interrupt status register 2 -volatile uint8_t ezmac_status; // ezmac status register - volatile int16_t afc_correction; // afc correction reading volatile int32_t afc_correction_Hz; // afc correction reading (in Hz) @@ -348,12 +486,6 @@ volatile int16_t temperature_reg; // the temperature sensor reading volatile uint8_t osc_load_cap; // xtal frequency calibration value -volatile uint8_t rssi; // the current RSSI (register value) -volatile int8_t rssi_dBm; // dBm value - -// the tx power register read back -volatile uint8_t tx_pwr; - // The transmit buffer. Holds data that is being transmitted. uint8_t tx_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4))); // The transmit buffer. Hosts data that is wating to be transmitted. @@ -373,18 +505,12 @@ volatile uint8_t rx_buffer[258] __attribute__ ((aligned(4))); volatile uint16_t rx_buffer_wr; // the received packet -volatile int8_t rx_packet_start_rssi_dBm; // volatile int8_t rx_packet_start_afc_Hz; // -volatile int8_t rx_packet_rssi_dBm; // the received packet signal strength volatile int8_t rx_packet_afc_Hz; // the receive packet frequency offset int lookup_index; int ss_lookup_index; -volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding. -volatile uint16_t rfm22_int_time_outs; // counter -volatile uint16_t prev_rfm22_int_time_outs; // - uint16_t timeout_ms = 20000; // uint16_t timeout_sync_ms = 3; // uint16_t timeout_data_ms = 20; // @@ -444,14 +570,23 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu rfm22b_dev->spi_id = spi_id; // Set the state to initializing. - rfm22b_dev->state = RFM22B_STATE_INITIALIZING; - rfm22b_dev->event = RFM22B_EVENT_NONE; + rfm22b_dev->state = RFM22B_STATE_UNINITIALIZED; + // Create the event queue + rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_rfm22b_event)); + + // Initialize the register values. + rfm22b_dev->device_status = 0; + rfm22b_dev->int_status1 = 0; + rfm22b_dev->int_status2 = 0; + rfm22b_dev->ezmac_status = 0; // Initialize the stats. rfm22b_dev->resets = 0; rfm22b_dev->errors = 0; rfm22b_dev->irqs_processed = 0; - + rfm22b_dev->rssi = 0; + rfm22b_dev->rssi_dBm = -127; + // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; @@ -464,6 +599,9 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Initialize the TX pre-buffer pointer. tx_pre_buffer_size = 0; + // Create the packet queue. + rfm22b_dev->packetQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); + // Initialize the max tx power level. PIOS_RFM22B_SetTxPower(*rfm22b_id, cfg->maxTxPower); @@ -482,49 +620,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Initialize the external interrupt. PIOS_EXTI_Init(cfg->exti_cfg); - // Initialize the radio device. - int initval = rfm22_init_normal(rfm22b_dev->deviceID, cfg->minFrequencyHz, cfg->maxFrequencyHz, 50000); - - if (initval < 0) - { - - // RF module error .. flash the LED's -#if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF(2, "RF ERROR res: %d\n\r\n\r", initval); -#endif - - for(unsigned int j = 0; j < 16; j++) - { - USB_LED_ON; - LINK_LED_ON; - RX_LED_OFF; - TX_LED_OFF; - - PIOS_DELAY_WaitmS(200); - - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_ON; - TX_LED_ON; - - PIOS_DELAY_WaitmS(200); - } - - PIOS_DELAY_WaitmS(1000); - - return initval; - } - - rfm22_setFreqCalibration(cfg->RFXtalCap); - rfm22_setNominalCarrierFrequency(cfg->frequencyHz); - rfm22_setDatarate(cfg->maxRFBandwidth, true); - - DEBUG_PRINTF(2, "\n\r"); - DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); - DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate()); - DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); - DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22b_dev->tx_power); - // Register the watchdog timer for the radio driver task #ifdef PIOS_WDG_RFM22B PIOS_WDG_RegisterFlag(PIOS_WDG_RFM22B); @@ -533,6 +628,9 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler. xTaskCreate(PIOS_RFM22B_Task, (signed char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void*)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle)); + // Initialize the radio device. + PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false); + return(0); } @@ -558,7 +656,8 @@ static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pio { // Store the event. - rfm22b_dev->event = event; + if (xQueueSend(rfm22b_dev->eventQueue, &event, portMAX_DELAY) != pdTRUE) + return; // Signal the semaphore to wake up the handler thread. if (inISR) { @@ -612,11 +711,6 @@ void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr) } } -int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) -{ - return rfm22_receivedRSSI(); -} - int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; @@ -633,6 +727,32 @@ static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) } +/** + * Insert a packet on the packet queue for sending. + * Note: If this finction succedds, the packet will be released by the driver, so no release is necessary. + * If this function doesn't success, the caller is still responsible for the packet. + * \param[in] rfm22b_id The rfm22b device. + * \param[in] p The packet handle. + * \param[in] max_delay The maximum time to delay waiting to queue the packet. + * \return true on success, false on failue to queue the packet. + */ +bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return false; + + // Store the packet handle in the packet queue + if (xQueueSend(rfm22b_dev->packetQueue, &p, max_delay) != pdTRUE) + return false; + + // Inject a send packet event + PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_SEND_PACKET, false); + + // Success + return true; +} + /** * The task that controls the radio state machine. */ @@ -654,7 +774,19 @@ static void PIOS_RFM22B_Task(void *parameters) if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { rfm22b_dev->irqs_processed++; lastEventTime = xTaskGetTickCount(); - rfm22_processInt(rfm22b_dev); + + // Process events through the state machine. + enum pios_rfm22b_event event; + while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) + { + if ((event == RFM22B_EVENT_INT_RECEIVED) && + ((rfm22b_dev->state == RFM22B_STATE_UNINITIALIZED) || (rfm22b_dev->state == RFM22B_STATE_INITIALIZING))) + continue; + + // Process all state transitions. + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); + } } else { @@ -663,21 +795,15 @@ static void PIOS_RFM22B_Task(void *parameters) if ((timeSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) { rfm22b_dev->resets++; - TX_LED_OFF; - TX_LED_OFF; - /* Clear the TX buffer in case we locked up in a transmit */ - tx_data_wr = 0; + // Transsition through an error event. + enum pios_rfm22b_event event = RFM22B_EVENT_ERROR; + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); - rfm22_init_normal(rfm22b_dev->deviceID, rfm22b_dev->cfg.minFrequencyHz, rfm22b_dev->cfg.maxFrequencyHz, 50000); - - /* Start a packet transfer if one is available. */ - rfm22b_dev->state = RFM22B_STATE_RX_WAIT_PREAMBLE; - if(rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE) - { - /* Switch to RX mode */ - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - } + // Clear the event queue. + while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) + ; } } } @@ -695,23 +821,8 @@ static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) tx_pre_buffer_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, tx_pre_buffer, TX_BUFFER_SIZE, NULL, &need_yield); - if(tx_pre_buffer_size > 0) - { - // already have data to be sent - if (tx_data_wr > 0) - return; - - // we are currently transmitting? - if (rfm22b_dev->state == RFM22B_STATE_TX_DATA) - return; - - // is the channel clear to transmit on? - if (!rfm22_channelIsClear()) - return; - - // Start the transmit - rfm22_txStart(); - } + // Inject a send packet event + PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_TX_START, false); } /** @@ -862,6 +973,39 @@ static uint8_t rfm22_read_noclaim(uint8_t addr) // ************************************ +static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event) +{ + + // No event + if (event == RFM22B_EVENT_NUM_EVENTS) + return RFM22B_EVENT_NUM_EVENTS; + + // Don't transition if there is no transition defined + enum pios_rfm22b_state next_state = rfm22b_transitions[rfm22b_dev->state].next_state[event]; + if (!next_state) + return RFM22B_EVENT_NUM_EVENTS; + + /* + * Move to the next state + * + * This is done prior to calling the new state's entry function to + * guarantee that the entry function never depends on the previous + * state. This way, it cannot ever know what the previous state was. + */ + enum pios_rfm22b_state prev_state = rfm22b_dev->state; + if (prev_state) ; + + rfm22b_dev->state = next_state; + + /* Call the entry function (if any) for the next state. */ + if (rfm22b_transitions[rfm22b_dev->state].entry_fn) + return rfm22b_transitions[rfm22b_dev->state].entry_fn(rfm22b_dev); + + return RFM22B_EVENT_NUM_EVENTS; +} + +// ************************************ + uint32_t rfm22_minFrequency(void) { return lower_carrier_frequency_limit_Hz; @@ -1107,7 +1251,7 @@ uint32_t rfm22_getDatarate(void) // ************************************ -static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state) +static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev) { exec_using_spi = true; @@ -1123,9 +1267,6 @@ static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state) // empty the rx buffer rx_buffer_wr = 0; - // reset the timer - rfm22_int_timer = 0; - g_rfm22b_dev->state = state; // Clear the TX buffer. tx_data_rd = tx_data_wr = 0; @@ -1144,17 +1285,20 @@ static void PIOS_RFM22B_SetRxMode(enum pios_rfm22b_event state) rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon); exec_using_spi = false; + + // No event generated + return RFM22B_EVENT_NUM_EVENTS; } // ************************************ -uint8_t rfm22_txStart() +static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) { if((tx_pre_buffer_size == 0) || (exec_using_spi == true)) { // Clear the TX buffer. tx_data_rd = tx_data_wr = 0; - return 0; + return RFM22B_EVENT_RX_MODE; } exec_using_spi = true; @@ -1211,13 +1355,6 @@ uint8_t rfm22_txStart() rfm22_deassertCs(); rfm22_releaseBus(); - // ******************* - - // reset the timer - rfm22_int_timer = 0; - - g_rfm22b_dev->state = RFM22B_STATE_TX_DATA; - // enable TX interrupts rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem); @@ -1227,35 +1364,76 @@ uint8_t rfm22_txStart() TX_LED_ON; exec_using_spi = false; - return 1; + return RFM22B_EVENT_NUM_EVENTS; } // ************************************ -// external interrupt line triggered (or polled) from the rf chip -void rfm22_processRxInt(struct pios_rfm22b_dev *rfm22b_dev) +/** + * Read the RFM22B interrupt and device status registers + * \param[in] rfm22b_dev The device structure + */ +static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev) { - register uint8_t int_stat1 = int_status1; - register uint8_t int_stat2 = int_status2; + exec_using_spi = true; - // FIFO under/over flow error. Restart RX mode. - if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) + // 1. Read the interrupt statuses with burst read + rfm22_claimBus(); // Set RC and the semaphore + uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF}; + uint8_t read_buf[3]; + rfm22_assertCs(); + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL); + rfm22_deassertCs(); + rfm22b_dev->int_status1 = read_buf[1]; + rfm22b_dev->int_status2 = read_buf[2]; + + // Device status + rfm22b_dev->device_status = rfm22_read_noclaim(RFM22_device_status); + + // EzMAC status + rfm22b_dev->ezmac_status = rfm22_read_noclaim(RFM22_ezmac_status); + + // Release the bus + rfm22_releaseBus(); + + // the RF module has gone and done a reset - we need to re-initialize the rf module + if (rfm22b_dev->int_status2 & RFM22_is2_ipor) { - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; + exec_using_spi = false; + return false; } + exec_using_spi = false; + return true; +} + +static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22b_dev) +{ + + // Read the device status registers + if (!rfm22_readStatus(rfm22b_dev)) + return RFM22B_EVENT_ERROR; + // Valid preamble detected - if (int_stat2 & RFM22_is2_ipreaval && (rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE)) + if (rfm22b_dev->int_status2 & RFM22_is2_ipreaval) { - rfm22b_dev->state = RFM22B_STATE_RX_WAIT_SYNC; RX_LED_ON; + return RFM22B_EVENT_PREAMBLE_DETECTED; } + return RFM22B_EVENT_NUM_EVENTS; +} + +static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_dev) +{ + + // Read the device status registers + if (!rfm22_readStatus(rfm22b_dev)) + return RFM22B_EVENT_ERROR; + // Sync word detected - if (int_stat2 & RFM22_is2_iswdet && ((rfm22b_dev->state == RFM22B_STATE_RX_WAIT_PREAMBLE || rfm22b_dev->state == RFM22B_STATE_RX_WAIT_SYNC))) + if (rfm22b_dev->int_status2 & RFM22_is2_iswdet) { - rfm22b_dev->state = RFM22B_STATE_RX_DATA; RX_LED_ON; // read the 10-bit signed afc correction value @@ -1267,65 +1445,65 @@ void rfm22_processRxInt(struct pios_rfm22b_dev *rfm22b_dev) // convert the afc value to Hz afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f); - // remember the rssi for this packet - rx_packet_start_rssi_dBm = rssi_dBm; + // read rx signal strength .. 45 = -100dBm, 205 = -20dBm + rfm22b_dev->rssi = rfm22_read(RFM22_rssi); + // convert to dBm + rfm22b_dev->rssi_dBm = (int8_t)(rfm22b_dev->rssi >> 1) - 122; + // remember the afc value for this packet rx_packet_start_afc_Hz = afc_correction_Hz; + + return RFM22B_EVENT_SYNC_DETECTED; } + return RFM22B_EVENT_NUM_EVENTS; +} + +static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) +{ + + // Read the device status registers + if (!rfm22_readStatus(rfm22b_dev)) + return RFM22B_EVENT_ERROR; + + // FIFO under/over flow error. Restart RX mode. + if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) + return RFM22B_EVENT_ERROR; + + exec_using_spi = true; + // RX FIFO almost full, it needs emptying - if (int_stat1 & RFM22_is1_irxffafull) + if (rfm22b_dev->int_status1 & RFM22_is1_irxffafull) { - if (rfm22b_dev->state == RFM22B_STATE_RX_DATA) - { - // read data from the rf chips FIFO buffer - // read the total length of the packet data - uint16_t len = rfm22_read(RFM22_received_packet_length); + // read data from the rf chips FIFO buffer + // read the total length of the packet data + uint16_t len = rfm22_read(RFM22_received_packet_length); - // The received packet is going to be larger than the specified length - if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) - { - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } + // The received packet is going to be larger than the specified length + if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) + return RFM22B_EVENT_ERROR; - // Another packet length error. - if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid)) - { - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } + // Another packet length error. + if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(rfm22b_dev->int_status1 & RFM22_is1_ipkvalid)) + return RFM22B_EVENT_ERROR; - // Fetch the data from the RX FIFO - rfm22_claimBus(); - rfm22_assertCs(); - PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); - rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, - (uint8_t *) &rx_buffer[rx_buffer_wr],RX_FIFO_HI_WATERMARK,NULL) == 0) ? - RX_FIFO_HI_WATERMARK : 0; - rfm22_deassertCs(); - rfm22_releaseBus(); - } else { - // Clear the RX FIFO - rfm22_claimBus(); - rfm22_assertCs(); - PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); - PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF,NULL,RX_FIFO_HI_WATERMARK,NULL); - rfm22_deassertCs(); - rfm22_releaseBus(); - } + // Fetch the data from the RX FIFO + rfm22_claimBus(); + rfm22_assertCs(); + PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); + rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, + (uint8_t *) &rx_buffer[rx_buffer_wr],RX_FIFO_HI_WATERMARK,NULL) == 0) ? + RX_FIFO_HI_WATERMARK : 0; + rfm22_deassertCs(); + rfm22_releaseBus(); } // CRC error .. discard the received data - if (int_stat1 & RFM22_is1_icrerror) - { - rfm22_int_timer = 0; // reset the timer - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } + if (rfm22b_dev->int_status1 & RFM22_is1_icrerror) + return RFM22B_EVENT_ERROR; // Valid packet received - if (int_stat1 & RFM22_is1_ipkvalid) + if (rfm22b_dev->int_status1 & RFM22_is1_ipkvalid) { // read the total length of the packet data @@ -1348,21 +1526,16 @@ void rfm22_processRxInt(struct pios_rfm22b_dev *rfm22b_dev) if (rx_buffer_wr != len) { - // we have a packet length error .. discard the packet - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; + exec_using_spi = false; + return RFM22B_EVENT_ERROR; } // we have a valid received packet if (rx_buffer_wr > 0) { - // remember the rssi for this packet - rx_packet_rssi_dBm = rx_packet_start_rssi_dBm; - // remember the afc offset for this packet - rx_packet_afc_Hz = rx_packet_start_afc_Hz; // Add the rssi and afc to the end of the packet. - rx_buffer[rx_buffer_wr++] = rx_packet_start_rssi_dBm; + rx_buffer[rx_buffer_wr++] = rfm22b_dev->rssi_dBm; rx_buffer[rx_buffer_wr++] = rx_packet_start_afc_Hz; // Pass this packet on bool need_yield = false; @@ -1372,51 +1545,31 @@ void rfm22_processRxInt(struct pios_rfm22b_dev *rfm22b_dev) rx_buffer_wr = 0; } - // Send a packet if it's available. - if(!rfm22_txStart()) - { - // Switch to RX mode - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - } + // Start a new transaction + exec_using_spi = false; + return RFM22B_EVENT_RX_COMPLETE; } + exec_using_spi = false; + return RFM22B_EVENT_NUM_EVENTS; } -void rfm22_processTxInt(struct pios_rfm22b_dev *rfm22b_dev) +static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) { - register uint8_t int_stat1 = int_status1; - // reset the timer - rfm22_int_timer = 0; + // Read the device status registers + if (!rfm22_readStatus(rfm22b_dev)) + return RFM22B_EVENT_ERROR; // FIFO under/over flow error. Back to RX mode. - if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) + if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } - - // Transmit timeout. Abort the transmit. - if (rfm22_int_timer >= timeout_data_ms) - { - rfm22_int_time_outs++; - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } - - // the rf module is not in tx mode - if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_tx) - { - if (rfm22_int_timer >= 100) - { - rfm22_int_time_outs++; - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); // back to rx mode - return; - } + exec_using_spi = false; + return RFM22B_EVENT_ERROR; } // TX FIFO almost empty, it needs filling up - if (int_stat1 & RFM22_is1_ixtffaem) + if (rfm22b_dev->int_status1 & RFM22_is1_ixtffaem) { // top-up the rf chips TX FIFO buffer uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; @@ -1432,117 +1585,15 @@ void rfm22_processTxInt(struct pios_rfm22b_dev *rfm22b_dev) } // Packet has been sent - if (int_stat1 & RFM22_is1_ipksent) + if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) { - - // Send another packet if it's available. - if(!rfm22_txStart()) - { - // Switch to RX mode - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - return; - } - } - -} - -static void rfm22_processInt(struct pios_rfm22b_dev *rfm22b_dev) -{ - // we haven't yet been initialized - if (!PIOS_RFM22B_validate(rfm22b_dev)) - return; - - exec_using_spi = true; - - // 1. Read the interrupt statuses with burst read - rfm22_claimBus(); // Set RC and the semaphore - uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF}; - uint8_t read_buf[3]; - rfm22_assertCs(); - PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL); - rfm22_deassertCs(); - int_status1 = read_buf[1]; - int_status2 = read_buf[2]; - - // Device status - device_status = rfm22_read_noclaim(RFM22_device_status); - - // EzMAC status - ezmac_status = rfm22_read_noclaim(RFM22_ezmac_status); - - // Release the bus - rfm22_releaseBus(); - - // Read the RSSI if we're in RX mode - if (rfm22b_dev->state != RFM22B_STATE_TX_DATA) - { - // read rx signal strength .. 45 = -100dBm, 205 = -20dBm - rssi = rfm22_read(RFM22_rssi); - // convert to dBm - rssi_dBm = (int8_t)(rssi >> 1) - 122; - } - else - // read the tx power register - tx_pwr = rfm22_read(RFM22_tx_power); - - // the RF module has gone and done a reset - we need to re-initialize the rf module - if (int_status2 & RFM22_is2_ipor) - { - rfm22b_dev->state = RFM22B_STATE_RESETTING; - // Need to do something here! - return; - } - - switch (rfm22b_dev->state) - { - case RFM22B_STATE_RX_WAIT_PREAMBLE: - case RFM22B_STATE_RX_WAIT_SYNC: - case RFM22B_STATE_RX_DATA: - - rfm22_processRxInt(rfm22b_dev); - break; - - case RFM22B_STATE_TX_DATA: - - rfm22_processTxInt(rfm22b_dev); - break; - - default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here - // to rx mode - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); - break; + exec_using_spi = false; + // Start a new transaction + return RFM22B_EVENT_TX_COMPLETE; } exec_using_spi = false; -} - -// ************************************ - -int8_t rfm22_getRSSI(void) -{ - exec_using_spi = true; - - rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm - rssi_dBm = (int8_t)(rssi >> 1) - 122; // convert to dBm - - exec_using_spi = false; - return rssi_dBm; -} - -int8_t rfm22_receivedRSSI(void) -{ // return the packets signal strength - if (!initialized) - return -127; - else - return rx_packet_rssi_dBm; -} - -int32_t rfm22_receivedAFCHz(void) -{ // return the packets offset frequency - if (!initialized) - return 0; - else - return rx_packet_afc_Hz; + return RFM22B_EVENT_NUM_EVENTS; } // ************************************ @@ -1566,7 +1617,7 @@ bool rfm22_channelIsClear(void) // we haven't yet been initialized return false; - if (g_rfm22b_dev->state != RFM22B_STATE_RX_WAIT_PREAMBLE && g_rfm22b_dev->state != RFM22B_STATE_RX_WAIT_SYNC) + if (g_rfm22b_dev->state != RFM22B_STATE_RX_MODE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_PREAMBLE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_SYNC) // we are receiving something or we are transmitting or we are scanning the spectrum return false; @@ -1599,20 +1650,20 @@ uint8_t rfm22_getFreqCalibration(void) } // ************************************ -// reset the RF module +// Initialise this hardware layer module and the rf module -int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_frequency_hz) +static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) { + uint32_t id = rfm22b_dev->deviceID; + uint32_t min_frequency_hz = rfm22b_dev->cfg.minFrequencyHz; + uint32_t max_frequency_hz = rfm22b_dev->cfg.maxFrequencyHz; + uint32_t freq_hop_step_size = 50000; + initialized = false; - - // **************** - exec_using_spi = true; - // **************** // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) - - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // wait 26ms PIOS_DELAY_WaitmS(26); @@ -1623,18 +1674,18 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq PIOS_DELAY_WaitmS(1); // read the status registers - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - if (int_status2 & RFM22_is2_ichiprdy) break; + rfm22b_dev->int_status1 = rfm22_read(RFM22_interrupt_status1); + rfm22b_dev->int_status2 = rfm22_read(RFM22_interrupt_status2); + if (rfm22b_dev->int_status2 & RFM22_is2_ichiprdy) break; } // **************** // read status - clears interrupt - device_status = rfm22_read(RFM22_device_status); - int_status1 = rfm22_read(RFM22_interrupt_status1); - int_status2 = rfm22_read(RFM22_interrupt_status2); - ezmac_status = rfm22_read(RFM22_ezmac_status); + rfm22b_dev->device_status = rfm22_read(RFM22_device_status); + rfm22b_dev->int_status1 = rfm22_read(RFM22_interrupt_status1); + rfm22b_dev->int_status2 = rfm22_read(RFM22_interrupt_status2); + rfm22b_dev->ezmac_status = rfm22_read(RFM22_ezmac_status); // disable all interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1646,16 +1697,10 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // **************** - g_rfm22b_dev->state = mode; - - device_status = int_status1 = int_status2 = ezmac_status = 0; - - rssi = 0; - rssi_dBm = -127; + rfm22b_dev->device_status = rfm22b_dev->int_status1 = rfm22b_dev->int_status2 = rfm22b_dev->ezmac_status = 0; rx_buffer_current = 0; rx_buffer_wr = 0; - rx_packet_rssi_dBm = -127; rx_packet_afc_Hz = 0; tx_data_rd = tx_data_wr = 0; @@ -1666,10 +1711,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq rf_bandwidth_used = 0; ss_rf_bandwidth_used = 0; - rfm22_int_timer = 0; - rfm22_int_time_outs = 0; - prev_rfm22_int_time_outs = 0; - hbsel = 0; frequency_step_size = 0.0f; @@ -1680,8 +1721,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq temperature_reg = 0; - tx_pwr = 0; - // **************** // read the RF chip ID bytes @@ -1698,19 +1737,16 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq #if defined(RFM22_DEBUG) DEBUG_PRINTF(2, "rf device type: INCORRECT - should be 0x08\n\r"); #endif - return -1; // incorrect RF module type + // incorrect RF module type + return RFM22B_EVENT_FATAL_ERROR; } - - // if (device_version != RFM22_DEVICE_VERSION_V2) // V2 - // return -2; // incorrect RF module version - // if (device_version != RFM22_DEVICE_VERSION_A0) // A0 - // return -2; // incorrect RF module version - if (device_version != RFM22_DEVICE_VERSION_B1) // B1 + if (device_version != RFM22_DEVICE_VERSION_B1) { #if defined(RFM22_DEBUG) DEBUG_PRINTF(2, "rf device version: INCORRECT\n\r"); #endif - return -2; // incorrect RF module version + // incorrect RF module version + return RFM22B_EVENT_FATAL_ERROR; } // **************** @@ -1752,7 +1788,7 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // choose the 3 GPIO pin functions rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value - if (g_rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { + if (rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) } else { @@ -1763,18 +1799,6 @@ int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_freq // **************** - return 0; // OK -} - -// ************************************ -// Initialise this hardware layer module and the rf module - -int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size) -{ - int res = rfm22_resetModule(RFM22B_STATE_RX_WAIT_PREAMBLE, min_frequency_hz, max_frequency_hz); - if (res < 0) - return res; - // initialize the frequency hopping step size freq_hop_step_size /= 10000; // in 10kHz increments if (freq_hop_step_size > 255) freq_hop_step_size = 255; @@ -1866,8 +1890,7 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set the tx power - rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | - RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power); + rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power); // TX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); @@ -1878,11 +1901,60 @@ int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequ // RX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); - PIOS_RFM22B_SetRxMode(RFM22B_STATE_RX_WAIT_PREAMBLE); + //rfm22_setRxMode(rfm22b_dev); + + rfm22_setFreqCalibration(rfm22b_dev->cfg.RFXtalCap); + rfm22_setNominalCarrierFrequency(rfm22b_dev->cfg.frequencyHz); + rfm22_setDatarate(rfm22b_dev->cfg.maxRFBandwidth, true); + + DEBUG_PRINTF(2, "\n\r"); + DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); + DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate()); + DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); + DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22b_dev->tx_power); initialized = true; - return 0; // ok + return RFM22B_EVENT_RX_MODE; +} + +static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) +{ + return RFM22B_EVENT_INITIALIZE; +} + +/** + * A fatal error has occured in the state machine. + * this should not happen. + * \parem [in] rfm22b_dev The device structure + * \return enum pios_rfm22b_event The next event to inject + */ +static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev) +{ + + // RF module error .. flash the LED's + for(unsigned int j = 0; j < 16; j++) + { + USB_LED_ON; + LINK_LED_ON; + RX_LED_OFF; + TX_LED_OFF; + + PIOS_DELAY_WaitmS(200); + + USB_LED_OFF; + LINK_LED_OFF; + RX_LED_ON; + TX_LED_ON; + + PIOS_DELAY_WaitmS(200); + } + + PIOS_DELAY_WaitmS(1000); + + PIOS_Assert(0); + + return RFM22B_EVENT_FATAL_ERROR; } // ************************************ diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 0cc685da3..451480960 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -31,6 +31,8 @@ #ifndef PIOS_RFM22B_H #define PIOS_RFM22B_H +#include + enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX}; /* Global Types */ @@ -51,9 +53,9 @@ struct pios_rfm22b_cfg { extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg); extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); -extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); -extern void PIOS_RFM22_processPendingISR(uint32_t wait_ms); +extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay); +extern uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay); #endif /* PIOS_RFM22B_H */ diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index ce6bf96f5..604efba63 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -598,16 +598,6 @@ uint32_t rfm22_freqHopSize(void); void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening); uint32_t rfm22_getDatarate(void); -int8_t rfm22_getRSSI(void); - -int8_t rfm22_receivedRSSI(void); -int32_t rfm22_receivedAFCHz(void); -uint16_t rfm22_receivedLength(void); -uint8_t * rfm22_receivedPointer(void); -void rfm22_receivedDone(void); - -int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately); - void rfm22_setFreqCalibration(uint8_t value); uint8_t rfm22_getFreqCalibration(void); @@ -627,16 +617,9 @@ bool rfm22_channelIsClear(void); bool rfm22_txReady(void); -void rfm22_1ms_tick(void); - void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function); void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function); -int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz); -int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz); -int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz); -int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size); - #endif /* PIOS_RFM22B_PRIV_H */ /** From a46e3cdec3bec787310d68738f9cc25cc00d3b6b Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sat, 22 Sep 2012 20:07:50 -0700 Subject: [PATCH 468/508] RFM22B: All outgoing data to the radio is now going through the PIOS_RFM22B_Send_Packet call. Also removed all global variables with the exception of the rx buffer. --- flight/Modules/Radio/radio.c | 31 +- .../PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h | 11 +- flight/PiOS/Common/pios_rfm22b.c | 502 ++++++------------ flight/PiOS/inc/pios_rfm22b_priv.h | 38 -- 4 files changed, 161 insertions(+), 421 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 7b61dce34..e1fab89f2 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -48,6 +48,7 @@ #define STATS_UPDATE_PERIOD_MS 500 #define RADIOSTATS_UPDATE_PERIOD_MS 250 #define MAX_LOST_CONTACT_TIME 4 +#define PACKET_MAX_DELAY 50 #ifndef LINK_LED_ON #define LINK_LED_ON @@ -73,7 +74,6 @@ typedef struct { // The task handles. xTaskHandle radioReceiveTaskHandle; xTaskHandle radioStatusTaskHandle; - xTaskHandle sendPacketTaskHandle; // Queue handles. xQueueHandle radioPacketQueue; @@ -106,7 +106,6 @@ typedef struct { static void radioReceiveTask(void *parameters); static void radioStatusTask(void *parameters); -static void sendPacketTask(void *parameters); static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc); static int32_t transmitPacket(PHPacketHandle packet); static void PPMHandler(uint16_t *channels); @@ -137,11 +136,9 @@ static int32_t RadioStart(void) // Start the tasks. xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle)); xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES * 2, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); - xTaskCreate(sendPacketTask, (signed char *)"SendPacket", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle)); // Install the monitors TaskMonitorAdd(TASKINFO_RUNNING_MODEMRX, data->radioReceiveTaskHandle); - TaskMonitorAdd(TASKINFO_RUNNING_MODEMTX, data->sendPacketTaskHandle); TaskMonitorAdd(TASKINFO_RUNNING_MODEMSTAT, data->radioStatusTaskHandle); // Register the watchdog timers. @@ -289,9 +286,6 @@ static int32_t RadioInitialize(void) PipXSettingsPairIDGet(&(data->pairStats[0].pairID)); data->destination_id = data->pairStats[0].pairID ? data->pairStats[0].pairID : 0xffffffff; - // Create the packet queue. - data->radioPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); - // Register the callbacks with the packet handler PHRegisterStatusHandler(pios_packet_handler, StatusHandler); PHRegisterOutputStream(pios_packet_handler, transmitPacket); @@ -342,27 +336,6 @@ static void radioReceiveTask(void *parameters) } } -/** - * Send packets to the radio. - */ -static void sendPacketTask(void *parameters) -{ - PHPacketHandle p; - - // Loop forever - while (1) { -#ifdef PIOS_INCLUDE_WDG - // Update the watchdog timer. - //PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET); -#endif /* PIOS_INCLUDE_WDG */ - // Wait for a packet on the queue. - if (xQueueReceive(data->radioPacketQueue, &p, MAX_PORT_DELAY) == pdTRUE) { - PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p)); - PHReleaseTXPacket(pios_packet_handler, p); - } - } -} - /** * Transmit a packet to the radio port. * \param[in] buf Data buffer to send @@ -374,7 +347,7 @@ static int32_t transmitPacket(PHPacketHandle p) { uint16_t len = PH_PACKET_SIZE(p); data->txBytes += len; - if (xQueueSend(data->radioPacketQueue, &p, portMAX_DELAY) != pdTRUE) + if (!PIOS_RFM22B_Send_Packet(pios_rfm22b_id, p, PACKET_MAX_DELAY)) return -1; return len; } diff --git a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h index d500c86ea..aaf265c58 100755 --- a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h @@ -71,13 +71,12 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 //------------------------ #define PIOS_WATCHDOG_TIMEOUT 500 #define PIOS_WDG_REGISTER BKP_DR4 -#define PIOS_WDG_COMUAVTALK 0x0001 -#define PIOS_WDG_RADIORECEIVE 0x0002 -#define PIOS_WDG_SENDPACKET 0x0004 +#define PIOS_WDG_COMGCS 0x0001 +#define PIOS_WDG_COMUAVTALK 0x0002 +#define PIOS_WDG_RADIORECEIVE 0x0004 #define PIOS_WDG_SENDDATA 0x0008 -#define PIOS_WDG_TRANSCOMM 0x0010 -#define PIOS_WDG_PPMINPUT 0x0020 -#define PIOS_WDG_COMGCS 0x0040 +#define PIOS_WDG_TRANSCOMM 0x0008 +#define PIOS_WDG_PPMINPUT 0x0010 //------------------------ // TELEMETRY diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 7a0e145dd..e48a97318 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -76,13 +76,9 @@ // ************************************ -#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms) - #define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles) #define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles) -// the size of the rf modules internal transmit buffers. -#define TX_BUFFER_SIZE 256 // the size of the rf modules internal FIFO buffers #define FIFO_SIZE 64 @@ -163,6 +159,7 @@ enum pios_rfm22b_state { enum pios_rfm22b_event { RFM22B_EVENT_INITIALIZE, + RFM22B_EVENT_INITIALIZED, RFM22B_EVENT_INT_RECEIVED, RFM22B_EVENT_TX_MODE, RFM22B_EVENT_RX_MODE, @@ -171,7 +168,9 @@ enum pios_rfm22b_event { RFM22B_EVENT_RX_COMPLETE, RFM22B_EVENT_SEND_PACKET, RFM22B_EVENT_TX_START, + RFM22B_EVENT_TX_STARTED, RFM22B_EVENT_TX_COMPLETE, + RFM22B_EVENT_TIMEOUT, RFM22B_EVENT_ERROR, RFM22B_EVENT_FATAL_ERROR, @@ -227,6 +226,23 @@ struct pios_rfm22b_dev { // The packet queue handle xQueueHandle packetQueue; + + // The current tx packet + PHPacketHandle tx_packet; + // the tx data read index + uint16_t tx_data_rd; + // the tx data write index + uint16_t tx_data_wr; + + // The frequency hopping step size + float frequency_step_size; + // current frequency hop channel + uint8_t frequency_hop_channel; + // the frequency hop step size + uint8_t frequency_hop_step_size_reg; + // afc correction reading (in Hz) + int32_t afc_correction_Hz; + int8_t rx_packet_start_afc_Hz; }; struct pios_rfm22b_transition { @@ -311,7 +327,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S [RFM22B_STATE_INITIALIZING] = { .entry_fn = rfm22_init, .next_state = { - [RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE, + [RFM22B_EVENT_INITIALIZED] = RFM22B_STATE_TX_START, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -327,7 +343,9 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S .entry_fn = rfm22_setRxMode, .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE, + [RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TX_START, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -337,7 +355,9 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE, [RFM22B_EVENT_PREAMBLE_DETECTED] = RFM22B_STATE_WAIT_SYNC, + [RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TX_START, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -393,34 +413,34 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S // xtal 10 ppm, 434MHz #define LOOKUP_SIZE 14 -const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; -const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}; -const uint32_t freq_deviation[] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000}; -const uint32_t rx_bandwidth[] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800}; -const int8_t est_rx_sens_dBm[] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3 +static const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000}; +static const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}; +static const uint32_t freq_deviation[] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000}; +static const uint32_t rx_bandwidth[] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800}; +static const int8_t est_rx_sens_dBm[] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3 -const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth +static const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth -const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override -const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control +static const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override +static const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control -const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override -const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio -const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2 -const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1 -const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0 -const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 -const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 +static const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override +static const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio +static const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2 +static const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1 +static const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0 +static const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 +static const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 -const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz +static const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz -const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 -const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 +static const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 +static const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 -const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1 -const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2 +static const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1 +static const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2 -const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation +static const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation // ************************************ // Scan Spectrum settings @@ -433,87 +453,29 @@ const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x #define SS_LOOKUP_SIZE 2 // xtal 1 ppm, 434MHz -const uint32_t ss_rx_bandwidth[] = { 2600, 10600}; +static const uint32_t ss_rx_bandwidth[] = { 2600, 10600}; -const uint8_t ss_reg_1C[] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth -const uint8_t ss_reg_1D[] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override +static const uint8_t ss_reg_1C[] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth +static const uint8_t ss_reg_1D[] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override -const uint8_t ss_reg_20[] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio -const uint8_t ss_reg_21[] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2 -const uint8_t ss_reg_22[] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1 -const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0 -const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 -const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 +static const uint8_t ss_reg_20[] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio +static const uint8_t ss_reg_21[] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2 +static const uint8_t ss_reg_22[] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1 +static const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0 +static const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 +static const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 -const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz +static const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz -const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 -const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 - -// ************************************ - -volatile bool initialized = false; - -#if defined(RFM22_EXT_INT_USE) -volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt -#endif - -uint8_t device_type; // the RF chips device ID number -uint8_t device_version; // the RF chips revision number - -uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use -uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use -uint32_t carrier_frequency_hz; // the current RF frequency we are on - -uint32_t carrier_datarate_bps; // the RF data rate we are using - -uint32_t rf_bandwidth_used; // the RF bandwidth currently used -uint32_t ss_rf_bandwidth_used; // the RF bandwidth currently used - -uint8_t hbsel; // holds the hbsel (1 or 2) -float frequency_step_size; // holds the minimum frequency step size - -uint8_t frequency_hop_channel; // current frequency hop channel - -uint8_t frequency_hop_step_size_reg; // - -uint8_t adc_config; // holds the adc config reg value - -volatile int16_t afc_correction; // afc correction reading -volatile int32_t afc_correction_Hz; // afc correction reading (in Hz) - -volatile int16_t temperature_reg; // the temperature sensor reading - -volatile uint8_t osc_load_cap; // xtal frequency calibration value - -// The transmit buffer. Holds data that is being transmitted. -uint8_t tx_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4))); -// The transmit buffer. Hosts data that is wating to be transmitted. -uint8_t tx_pre_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4))); -// The tx pre-buffer write index. -uint16_t tx_pre_buffer_size; -// the tx data read index -volatile uint16_t tx_data_rd; -// the tx data write index -volatile uint16_t tx_data_wr; +static const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 +static const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 // the current receive buffer in use (double buffer) volatile uint8_t rx_buffer_current; // the receive buffer .. received packet data is saved here volatile uint8_t rx_buffer[258] __attribute__ ((aligned(4))); // the receive buffer write index -volatile uint16_t rx_buffer_wr; - -// the received packet -volatile int8_t rx_packet_start_afc_Hz; // -volatile int8_t rx_packet_afc_Hz; // the receive packet frequency offset - -int lookup_index; -int ss_lookup_index; - -uint16_t timeout_ms = 20000; // -uint16_t timeout_sync_ms = 3; // -uint16_t timeout_data_ms = 20; // +volatile uint16_t rx_buffer_wr; static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev) @@ -596,9 +558,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary( rfm22b_dev->isrPending ); - // Initialize the TX pre-buffer pointer. - tx_pre_buffer_size = 0; - // Create the packet queue. rfm22b_dev->packetQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); @@ -804,6 +763,13 @@ static void PIOS_RFM22B_Task(void *parameters) // Clear the event queue. while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) ; + lastEventTime = xTaskGetTickCount(); + } + else + { + enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); } } } @@ -815,6 +781,7 @@ static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) bool valid = PIOS_RFM22B_validate(rfm22b_dev); PIOS_Assert(valid); +#ifdef NEVER // Get some data to send bool need_yield = false; if(tx_pre_buffer_size == 0) @@ -823,6 +790,7 @@ static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail) // Inject a send packet event PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_TX_START, false); +#endif } /** @@ -1006,27 +974,17 @@ static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_ // ************************************ -uint32_t rfm22_minFrequency(void) +static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t frequency_hz) { - return lower_carrier_frequency_limit_Hz; -} -uint32_t rfm22_maxFrequency(void) -{ - return upper_carrier_frequency_limit_Hz; -} - -void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) -{ - - exec_using_spi = true; - - // ******* - - if (frequency_hz < lower_carrier_frequency_limit_Hz) - frequency_hz = lower_carrier_frequency_limit_Hz; - else if (frequency_hz > upper_carrier_frequency_limit_Hz) - frequency_hz = upper_carrier_frequency_limit_Hz; + uint32_t min_frequency_hz = rfm22b_dev->cfg.minFrequencyHz; + uint32_t max_frequency_hz = rfm22b_dev->cfg.maxFrequencyHz; + if (frequency_hz < min_frequency_hz) + frequency_hz = min_frequency_hz; + else if (frequency_hz > max_frequency_hz) + frequency_hz = max_frequency_hz; + // holds the hbsel (1 or 2) + uint8_t hbsel; if (frequency_hz < 480000000) hbsel = 1; else @@ -1038,59 +996,37 @@ void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz) fc = (fc * 64u) / (10000ul * hbsel); fb -= 24; - // carrier_frequency_hz = frequency_hz; - carrier_frequency_hz = ((uint32_t)fb + 24 + ((float)fc / 64000)) * 10000000 * hbsel; - if (hbsel > 1) fb |= RFM22_fbs_hbsel; fb |= RFM22_fbs_sbse; // is this the RX LO polarity? - frequency_step_size = 156.25f * hbsel; + // frequency hopping channel (0-255) + rfm22b_dev->frequency_step_size = 156.25f * hbsel; - rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hopping channel (0-255) + // frequency hopping channel (0-255) + rfm22_write(RFM22_frequency_hopping_channel_select, rfm22b_dev->frequency_hop_channel); - rfm22_write(RFM22_frequency_offset1, 0); // no frequency offset - rfm22_write(RFM22_frequency_offset2, 0); // no frequency offset + // no frequency offset + rfm22_write(RFM22_frequency_offset1, 0); + // no frequency offset + rfm22_write(RFM22_frequency_offset2, 0); - rfm22_write(RFM22_frequency_band_select, fb); // set the carrier frequency - rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); // " " - rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); // " " - - // ******* - -#if defined(RFM22_DEBUG) - //DEBUG_PRINTF(2, "rf setFreq: %u\n\r", carrier_frequency_hz); - // DEBUG_PRINTF(2, "rf setFreq frequency_step_size: %0.2f\n\r", frequency_step_size); -#endif - - exec_using_spi = false; -} - -uint32_t rfm22_getNominalCarrierFrequency(void) -{ - return carrier_frequency_hz; -} - -float rfm22_getFrequencyStepSize(void) -{ - return frequency_step_size; + // set the carrier frequency + rfm22_write(RFM22_frequency_band_select, fb); + rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); + rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); } void rfm22_setFreqHopChannel(uint8_t channel) { // set the frequency hopping channel - frequency_hop_channel = channel; - rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); -} - -uint8_t rfm22_freqHopChannel(void) -{ // return the current frequency hopping channel - return frequency_hop_channel; + g_rfm22b_dev->frequency_hop_channel = channel; + rfm22_write(RFM22_frequency_hopping_channel_select, channel); } uint32_t rfm22_freqHopSize(void) { // return the frequency hopping step size - return ((uint32_t)frequency_hop_step_size_reg * 10000); + return ((uint32_t)g_rfm22b_dev->frequency_hop_step_size_reg * 10000); } // ************************************ @@ -1109,15 +1045,12 @@ uint32_t rfm22_freqHopSize(void) void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) { - exec_using_spi = true; - - lookup_index = 0; + // Find the closest data rate that is >= the value passed in + int lookup_index = 0; while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) lookup_index++; - carrier_datarate_bps = datarate_bps = data_rate[lookup_index]; - - rf_bandwidth_used = rx_bandwidth[lookup_index]; + datarate_bps = data_rate[lookup_index]; // rfm22_if_filter_bandwidth rfm22_write(0x1C, reg_1C[lookup_index]); @@ -1145,7 +1078,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) // rfm22_afc_limiter rfm22_write(0x2A, reg_2A[lookup_index]); - if (carrier_datarate_bps < 100000) + if (datarate_bps < 100000) // rfm22_chargepump_current_trimming_override rfm22_write(0x58, 0x80); else @@ -1176,84 +1109,12 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) rfm22_write(RFM22_ook_counter_value1, 0x00); rfm22_write(RFM22_ook_counter_value2, 0x00); - - // ******************************** - // calculate the TX register values - /* - uint16_t fd = frequency_deviation / 625; - - uint8_t mmc1 = RFM22_mmc1_enphpwdn | RFM22_mmc1_manppol; - uint16_t txdr; - if (datarate_bps < 30000) - { - txdr = (datarate_bps * 20972) / 10000; - mmc1 |= RFM22_mmc1_txdtrtscale; - } - else - txdr = (datarate_bps * 6553) / 100000; - - uint8_t mmc2 = RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk; // FIFO mode, GFSK - // uint8_t mmc2 = RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE - if (fd & 0x100) mmc2 |= RFM22_mmc2_fd; - - rfm22_write(RFM22_frequency_deviation, fd); // set the TX peak frequency deviation - - rfm22_write(RFM22_modulation_mode_control1, mmc1); - rfm22_write(RFM22_modulation_mode_control2, mmc2); - - rfm22_write(RFM22_tx_data_rate1, txdr >> 8); // set the TX data rate - rfm22_write(RFM22_tx_data_rate0, txdr); // " " - */ - // ******************************** - // determine a clear channel time - - // initialise the stopwatch with a suitable resolution for the datarate - //STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate - - // ******************************** - // determine suitable time-out periods - - // milliseconds - timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps; - if (timeout_sync_ms < 3) - // because out timer resolution is only 1ms - timeout_sync_ms = 3; - - // milliseconds - timeout_data_ms = (8000ul * 100) / carrier_datarate_bps; - if (timeout_data_ms < 3) - // because out timer resolution is only 1ms - timeout_data_ms = 3; - - // ******************************** - -#if defined(RFM22_DEBUG) -/* - DEBUG_PRINTF(2, "rf datarate_bps: %d\n\r", datarate_bps); - DEBUG_PRINTF(2, "rf frequency_deviation: %d\n\r", frequency_deviation); - uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz - uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation); - DEBUG_PRINTF(2, "rf modulation_bandwidth: %u\n\r", modulation_bandwidth); - DEBUG_PRINTF(2, "rf_rx_bandwidth[%u]: %u\n\r", lookup_index, rx_bandwidth[lookup_index]); - DEBUG_PRINTF(2, "rf est rx sensitivity[%u]: %ddBm\n\r", lookup_index, est_rx_sens_dBm[lookup_index]); -*/ -#endif - - // ******* - - exec_using_spi = false; -} - -uint32_t rfm22_getDatarate(void) -{ - return carrier_datarate_bps; } // ************************************ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev) { - exec_using_spi = true; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1269,7 +1130,7 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev rx_buffer_wr = 0; // Clear the TX buffer. - tx_data_rd = tx_data_wr = 0; + rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; // clear FIFOs rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx); @@ -1284,8 +1145,6 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev // enable the receiver rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon); - exec_using_spi = false; - // No event generated return RFM22B_EVENT_NUM_EVENTS; } @@ -1294,14 +1153,15 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) { - if((tx_pre_buffer_size == 0) || (exec_using_spi == true)) + // See if there's a packet on the packet queue. + PHPacketHandle p; + if (xQueueReceive(rfm22b_dev->packetQueue, &p, 0) != pdTRUE) { // Clear the TX buffer. - tx_data_rd = tx_data_wr = 0; + rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; return RFM22B_EVENT_RX_MODE; } - - exec_using_spi = true; + rfm22b_dev->tx_packet = p; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1311,15 +1171,13 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // Queue the data up for sending - memcpy(tx_buffer, tx_pre_buffer, tx_pre_buffer_size); - tx_data_rd = 0; - tx_data_wr = tx_pre_buffer_size; - tx_pre_buffer_size = 0; + rfm22b_dev->tx_data_wr = PH_PACKET_SIZE(rfm22b_dev->tx_packet); RX_LED_OFF; // Set the destination address in the transmit header. // The destination address is the first 4 bytes of the message. + uint8_t *tx_buffer = (uint8_t*)(rfm22b_dev->tx_packet); rfm22_write(RFM22_transmit_header0, tx_buffer[0]); rfm22_write(RFM22_transmit_header1, tx_buffer[1]); rfm22_write(RFM22_transmit_header2, tx_buffer[2]); @@ -1342,16 +1200,16 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) // add some data to the chips TX FIFO before enabling the transmitter // set the total number of data bytes we are going to transmit - rfm22_write(RFM22_transmit_packet_length, tx_data_wr); + rfm22_write(RFM22_transmit_packet_length, rfm22b_dev->tx_data_wr); // add some data rfm22_claimBus(); rfm22_assertCs(); PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80); - int bytes_to_write = (tx_data_wr - tx_data_rd); + int bytes_to_write = (rfm22b_dev->tx_data_wr - rfm22b_dev->tx_data_rd); bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write; - PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); - tx_data_rd += bytes_to_write; + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL); + rfm22b_dev->tx_data_rd += bytes_to_write; rfm22_deassertCs(); rfm22_releaseBus(); @@ -1363,8 +1221,7 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) TX_LED_ON; - exec_using_spi = false; - return RFM22B_EVENT_NUM_EVENTS; + return RFM22B_EVENT_TX_STARTED; } // ************************************ @@ -1375,7 +1232,6 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) */ static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev) { - exec_using_spi = true; // 1. Read the interrupt statuses with burst read rfm22_claimBus(); // Set RC and the semaphore @@ -1398,12 +1254,8 @@ static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev) // the RF module has gone and done a reset - we need to re-initialize the rf module if (rfm22b_dev->int_status2 & RFM22_is2_ipor) - { - exec_using_spi = false; return false; - } - exec_using_spi = false; return true; } @@ -1438,12 +1290,12 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de // read the 10-bit signed afc correction value // bits 9 to 2 - afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8; + uint16_t afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8; // bits 1 & 0 afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0; afc_correction >>= 6; // convert the afc value to Hz - afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f); + rfm22b_dev->afc_correction_Hz = (int32_t)(rfm22b_dev->frequency_step_size * afc_correction + 0.5f); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm rfm22b_dev->rssi = rfm22_read(RFM22_rssi); @@ -1451,7 +1303,7 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de rfm22b_dev->rssi_dBm = (int8_t)(rfm22b_dev->rssi >> 1) - 122; // remember the afc value for this packet - rx_packet_start_afc_Hz = afc_correction_Hz; + rfm22b_dev->rx_packet_start_afc_Hz = rfm22b_dev->afc_correction_Hz; return RFM22B_EVENT_SYNC_DETECTED; } @@ -1470,8 +1322,6 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) return RFM22B_EVENT_ERROR; - exec_using_spi = true; - // RX FIFO almost full, it needs emptying if (rfm22b_dev->int_status1 & RFM22_is1_irxffafull) { @@ -1525,10 +1375,7 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) } if (rx_buffer_wr != len) - { - exec_using_spi = false; return RFM22B_EVENT_ERROR; - } // we have a valid received packet @@ -1536,7 +1383,7 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) { // Add the rssi and afc to the end of the packet. rx_buffer[rx_buffer_wr++] = rfm22b_dev->rssi_dBm; - rx_buffer[rx_buffer_wr++] = rx_packet_start_afc_Hz; + rx_buffer[rx_buffer_wr++] = rfm22b_dev->rx_packet_start_afc_Hz; // Pass this packet on bool need_yield = false; if (rfm22b_dev->rx_in_cb) @@ -1546,11 +1393,9 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) } // Start a new transaction - exec_using_spi = false; return RFM22B_EVENT_RX_COMPLETE; } - exec_using_spi = false; return RFM22B_EVENT_NUM_EVENTS; } @@ -1559,12 +1404,21 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) // Read the device status registers if (!rfm22_readStatus(rfm22b_dev)) + { + // Free the tx packet + PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet); + rfm22b_dev->tx_packet = 0; + rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; return RFM22B_EVENT_ERROR; + } // FIFO under/over flow error. Back to RX mode. if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl)) { - exec_using_spi = false; + // Free the tx packet + PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet); + rfm22b_dev->tx_packet = 0; + rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; return RFM22B_EVENT_ERROR; } @@ -1572,14 +1426,15 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) if (rfm22b_dev->int_status1 & RFM22_is1_ixtffaem) { // top-up the rf chips TX FIFO buffer + uint8_t *tx_buffer = (uint8_t*)(rfm22b_dev->tx_packet); uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1; rfm22_claimBus(); rfm22_assertCs(); PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80); - int bytes_to_write = (tx_data_wr - tx_data_rd); + int bytes_to_write = (rfm22b_dev->tx_data_wr - rfm22b_dev->tx_data_rd); bytes_to_write = (bytes_to_write > max_bytes) ? max_bytes: bytes_to_write; - PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[tx_data_rd], NULL, bytes_to_write, NULL); - tx_data_rd += bytes_to_write; + PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL); + rfm22b_dev->tx_data_rd += bytes_to_write; rfm22_deassertCs(); rfm22_releaseBus(); } @@ -1587,12 +1442,14 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) // Packet has been sent if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) { - exec_using_spi = false; + // Free the tx packet + PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet); + rfm22b_dev->tx_packet = 0; + rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; // Start a new transaction return RFM22B_EVENT_TX_COMPLETE; } - exec_using_spi = false; return RFM22B_EVENT_NUM_EVENTS; } @@ -1613,10 +1470,6 @@ bool rfm22_transmitting(void) // return true if the channel is clear to transmit on bool rfm22_channelIsClear(void) { - if (!initialized) - // we haven't yet been initialized - return false; - if (g_rfm22b_dev->state != RFM22B_STATE_RX_MODE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_PREAMBLE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_SYNC) // we are receiving something or we are transmitting or we are scanning the spectrum return false; @@ -1624,29 +1477,12 @@ bool rfm22_channelIsClear(void) return true; } -// return true if the transmiter is ready for use -bool rfm22_txReady(void) -{ - return (tx_data_rd == 0 && tx_data_wr == 0 && g_rfm22b_dev->state != RFM22B_STATE_TX_DATA); -} - // ************************************ // set/get the frequency calibration value void rfm22_setFreqCalibration(uint8_t value) { - osc_load_cap = value; - - exec_using_spi = true; - - rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); - - exec_using_spi = false; -} - -uint8_t rfm22_getFreqCalibration(void) -{ - return osc_load_cap; + rfm22_write(RFM22_xtal_osc_load_cap, value); } // ************************************ @@ -1659,9 +1495,6 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) uint32_t max_frequency_hz = rfm22b_dev->cfg.maxFrequencyHz; uint32_t freq_hop_step_size = 50000; - initialized = false; - exec_using_spi = true; - // software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B) rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); @@ -1693,39 +1526,25 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // **************** - exec_using_spi = false; - - // **************** - rfm22b_dev->device_status = rfm22b_dev->int_status1 = rfm22b_dev->int_status2 = rfm22b_dev->ezmac_status = 0; rx_buffer_current = 0; rx_buffer_wr = 0; - rx_packet_afc_Hz = 0; - tx_data_rd = tx_data_wr = 0; + rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; + rfm22b_dev->tx_packet = NULL; - lookup_index = 0; - ss_lookup_index = 0; + rfm22b_dev->frequency_hop_channel = 0; - rf_bandwidth_used = 0; - ss_rf_bandwidth_used = 0; - - hbsel = 0; - frequency_step_size = 0.0f; - - frequency_hop_channel = 0; - - afc_correction = 0; - afc_correction_Hz = 0; - - temperature_reg = 0; + rfm22b_dev->afc_correction_Hz = 0; // **************** // read the RF chip ID bytes - device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; // read the device type - device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; // read the device version + // read the device type + uint8_t device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; + // read the device version + uint8_t device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; #if defined(RFM22_DEBUG) DEBUG_PRINTF(2, "rf device type: %d\n\r", device_type); @@ -1767,27 +1586,24 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) max_frequency_hz = tmp; } - lower_carrier_frequency_limit_Hz = min_frequency_hz; - upper_carrier_frequency_limit_Hz = max_frequency_hz; - // **************** // calibrate our RF module to be exactly on frequency .. different for every module - - osc_load_cap = OSC_LOAD_CAP; // default - rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap); + rfm22_write(RFM22_xtal_osc_load_cap, OSC_LOAD_CAP); // **************** // disable Low Duty Cycle Mode rfm22_write(RFM22_op_and_func_ctrl2, 0x00); - rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output + // 1MHz clock output + rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); - rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode - // rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode + // READY mode + rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // choose the 3 GPIO pin functions - rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value + // GPIO port use default value + rfm22_write(RFM22_io_port_config, RFM22_io_port_default); if (rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) { rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch) rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch) @@ -1802,7 +1618,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // initialize the frequency hopping step size freq_hop_step_size /= 10000; // in 10kHz increments if (freq_hop_step_size > 255) freq_hop_step_size = 255; - frequency_hop_step_size_reg = freq_hop_step_size; + rfm22b_dev->frequency_hop_step_size_reg = freq_hop_step_size; // set the RF datarate rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, true); @@ -1814,7 +1630,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // setup to read the internal temperature sensor // ADC used to sample the temperature sensor - adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg; + uint8_t adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg; rfm22_write(RFM22_adc_config, adc_config); // adc offset @@ -1875,7 +1691,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); #endif - // sync word + // sync word rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); rfm22_write(RFM22_sync_word1, SYNC_BYTE_3); @@ -1884,10 +1700,10 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen); // set frequency hopping channel step size (multiples of 10kHz) - rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); + rfm22_write(RFM22_frequency_hopping_step_size, rfm22b_dev->frequency_hop_step_size_reg); // set our nominal carrier frequency - rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); + rfm22_setNominalCarrierFrequency(rfm22b_dev, (min_frequency_hz + max_frequency_hz) / 2); // set the tx power rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power); @@ -1901,21 +1717,11 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // RX FIFO Almost Full Threshold (0 - 63) rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); - //rfm22_setRxMode(rfm22b_dev); - rfm22_setFreqCalibration(rfm22b_dev->cfg.RFXtalCap); - rfm22_setNominalCarrierFrequency(rfm22b_dev->cfg.frequencyHz); + rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->cfg.frequencyHz); rfm22_setDatarate(rfm22b_dev->cfg.maxRFBandwidth, true); - DEBUG_PRINTF(2, "\n\r"); - DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); - DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate()); - DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency()); - DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22b_dev->tx_power); - - initialized = true; - - return RFM22B_EVENT_RX_MODE; + return RFM22B_EVENT_INITIALIZED; } static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 604efba63..cea382220 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -582,44 +582,6 @@ typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len); void PIOS_RFM22_EXT_Int(void); -uint32_t rfm22_minFrequency(void); -uint32_t rfm22_maxFrequency(void); - -void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz); -uint32_t rfm22_getNominalCarrierFrequency(void); - -float rfm22_getFrequencyStepSize(void); - -void rfm22_setFreqHopChannel(uint8_t channel); -uint8_t rfm22_freqHopChannel(void); - -uint32_t rfm22_freqHopSize(void); - -void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening); -uint32_t rfm22_getDatarate(void); - -void rfm22_setFreqCalibration(uint8_t value); -uint8_t rfm22_getFreqCalibration(void); - -void rfm22_setTxPower(uint8_t tx_pwr); -uint8_t rfm22_getTxPower(void); - -void rfm22_setTxStream(void); // TEST ONLY - -void rfm22_setTxNormal(void); -void rfm22_setTxCarrierMode(void); -void rfm22_setTxPNMode(void); - -int8_t rfm22_currentMode(void); -bool rfm22_transmitting(void); - -bool rfm22_channelIsClear(void); - -bool rfm22_txReady(void); - -void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function); -void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function); - #endif /* PIOS_RFM22B_PRIV_H */ /** From a070e1cc3e772252d2552e90a8d6794aaf10c2dd Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Sun, 23 Sep 2012 08:36:38 -0700 Subject: [PATCH 469/508] RFM22B: Added PIOS_RFM22B_Receive_Packet function and removed rx buffer. --- flight/Modules/Radio/radio.c | 31 ++------ flight/PiOS/Common/pios_rfm22b.c | 119 +++++++++++++++++++++++-------- 2 files changed, 93 insertions(+), 57 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index e1fab89f2..41e732215 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -41,7 +41,7 @@ // **************** // Private constants -#define STACK_SIZE_BYTES 150 +#define STACK_SIZE_BYTES 200 #define TASK_PRIORITY (tskIDLE_PRIORITY + 2) #define PACKET_QUEUE_SIZE PIOS_PH_WIN_SIZE #define MAX_PORT_DELAY 200 @@ -232,20 +232,8 @@ static int32_t RadioInitialize(void) } /* Initalize the RFM22B radio COM device. */ - { - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg.slave_num, &pios_rfm22b_cfg)) { - return -1; - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg.slave_num, &pios_rfm22b_cfg)) + return -1; // Initialize the packet handler PacketHandlerConfig pios_ph_cfg = { @@ -311,18 +299,9 @@ static void radioReceiveTask(void *parameters) PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE); #endif /* PIOS_INCLUDE_WDG */ - // Get a RX packet from the packet handler if required. - if (p == NULL) - p = PHGetRXPacket(pios_packet_handler); - - if(p == NULL) { - // Wait a bit for a packet to come available. - vTaskDelay(5); - continue; - } - // Receive data from the radio port - rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY); + p = NULL; + rx_bytes = PIOS_RFM22B_Receive_Packet(pios_rfm22b_id, &p, MAX_PORT_DELAY); if(rx_bytes == 0) continue; data->rxBytes += rx_bytes; diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index e48a97318..723337e46 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -192,6 +192,9 @@ struct pios_rfm22b_dev { // ISR pending xSemaphoreHandle isrPending; + // Receive packet complete + xSemaphoreHandle rxsem; + // The COM callback functions. pios_com_callback rx_in_cb; uint32_t rx_in_context; @@ -234,6 +237,17 @@ struct pios_rfm22b_dev { // the tx data write index uint16_t tx_data_wr; + // The current rx packet + PHPacketHandle rx_packet; + // The previous rx packet + PHPacketHandle rx_packet_prev; + // The next rx packet + PHPacketHandle rx_packet_next; + // the receive buffer write index + uint16_t rx_buffer_wr; + // the receive buffer write index + uint16_t rx_packet_len; + // The frequency hopping step size float frequency_step_size; // current frequency hop channel @@ -470,13 +484,6 @@ static const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_p static const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 static const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 -// the current receive buffer in use (double buffer) -volatile uint8_t rx_buffer_current; -// the receive buffer .. received packet data is saved here -volatile uint8_t rx_buffer[258] __attribute__ ((aligned(4))); -// the receive buffer write index -volatile uint16_t rx_buffer_wr; - static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev) { @@ -552,12 +559,22 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; + // Initialize the packets. + rfm22b_dev->rx_packet = NULL; + rfm22b_dev->rx_packet_next = NULL; + rfm22b_dev->rx_packet_prev = NULL; + rfm22b_dev->rx_packet_len = 0; + rfm22b_dev->tx_packet = NULL; + *rfm22b_id = (uint32_t)rfm22b_dev; g_rfm22b_dev = rfm22b_dev; // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary( rfm22b_dev->isrPending ); + // Create a semaphore to know when an rx packet is available + vSemaphoreCreateBinary( rfm22b_dev->rxsem ); + // Create the packet queue. rfm22b_dev->packetQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); @@ -712,6 +729,39 @@ bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_ return true; } +/** + * Receive a packet from the radio. + * \param[in] rfm22b_id The rfm22b device. + * \param[in] p A pointer to the packet handle. + * \param[in] max_delay The maximum time to delay waiting for a packet. + * \return The number of bytes received. + */ +uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay) +{ + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if (!PIOS_RFM22B_validate(rfm22b_dev)) + return 0; + + // Allocate the next Rx packet + if (rfm22b_dev->rx_packet_next == NULL) + rfm22b_dev->rx_packet_next = PHGetRXPacket(pios_packet_handler); + + // Block on the semephore until the a packet has been received. + if (xSemaphoreTake(rfm22b_dev->rxsem, max_delay / portTICK_RATE_MS) != pdTRUE) + return 0; + + // Return the Rx packet if it's available. + uint32_t rx_len = 0; + if (rfm22b_dev->rx_packet_prev) + { + *p = rfm22b_dev->rx_packet_prev; + rfm22b_dev->rx_packet_prev = NULL; + rx_len = rfm22b_dev->rx_packet_len; + } + + return rx_len; +} + /** * The task that controls the radio state machine. */ @@ -1127,7 +1177,7 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev TX_LED_OFF; // empty the rx buffer - rx_buffer_wr = 0; + rfm22b_dev->rx_buffer_wr = 0; // Clear the TX buffer. rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; @@ -1313,6 +1363,15 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) { + // Swap in the next packet buffer if required. + if (rfm22b_dev->rx_packet == NULL) + { + if (rfm22b_dev->rx_packet_next != NULL) + rfm22b_dev->rx_packet = rfm22b_dev->rx_packet_next; + else + return RFM22B_EVENT_ERROR; + } + uint8_t *rx_buffer = (uint8_t*)(rfm22b_dev->rx_packet); // Read the device status registers if (!rfm22_readStatus(rfm22b_dev)) @@ -1330,20 +1389,18 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) uint16_t len = rfm22_read(RFM22_received_packet_length); // The received packet is going to be larger than the specified length - if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) + if ((rfm22b_dev->rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len) return RFM22B_EVENT_ERROR; // Another packet length error. - if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(rfm22b_dev->int_status1 & RFM22_is1_ipkvalid)) + if (((rfm22b_dev->rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(rfm22b_dev->int_status1 & RFM22_is1_ipkvalid)) return RFM22B_EVENT_ERROR; // Fetch the data from the RX FIFO rfm22_claimBus(); rfm22_assertCs(); PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); - rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, - (uint8_t *) &rx_buffer[rx_buffer_wr],RX_FIFO_HI_WATERMARK,NULL) == 0) ? - RX_FIFO_HI_WATERMARK : 0; + rfm22b_dev->rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id ,OUT_FF, (uint8_t *)&rx_buffer[rfm22b_dev->rx_buffer_wr], RX_FIFO_HI_WATERMARK, NULL) == 0) ? RX_FIFO_HI_WATERMARK : 0; rfm22_deassertCs(); rfm22_releaseBus(); } @@ -1360,36 +1417,38 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) uint32_t len = rfm22_read(RFM22_received_packet_length); // their must still be data in the RX FIFO we need to get - if (rx_buffer_wr < len) + if (rfm22b_dev->rx_buffer_wr < len) { - int32_t bytes_to_read = len - rx_buffer_wr; + int32_t bytes_to_read = len - rfm22b_dev->rx_buffer_wr; // Fetch the data from the RX FIFO rfm22_claimBus(); rfm22_assertCs(); PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F); - rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, - (uint8_t *) &rx_buffer[rx_buffer_wr],bytes_to_read,NULL) == 0) ? - bytes_to_read : 0; + rfm22b_dev->rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, (uint8_t *)&rx_buffer[rfm22b_dev->rx_buffer_wr], bytes_to_read, NULL) == 0) ? bytes_to_read : 0; rfm22_deassertCs(); rfm22_releaseBus(); } - if (rx_buffer_wr != len) + if (rfm22b_dev->rx_buffer_wr != len) return RFM22B_EVENT_ERROR; // we have a valid received packet - if (rx_buffer_wr > 0) + if (rfm22b_dev->rx_buffer_wr > 0) { // Add the rssi and afc to the end of the packet. - rx_buffer[rx_buffer_wr++] = rfm22b_dev->rssi_dBm; - rx_buffer[rx_buffer_wr++] = rfm22b_dev->rx_packet_start_afc_Hz; - // Pass this packet on - bool need_yield = false; - if (rfm22b_dev->rx_in_cb) - (rfm22b_dev->rx_in_cb)(rfm22b_dev->rx_in_context, (uint8_t*)rx_buffer, - rx_buffer_wr, NULL, &need_yield); - rx_buffer_wr = 0; + rx_buffer[rfm22b_dev->rx_buffer_wr++] = rfm22b_dev->rssi_dBm; + rx_buffer[rfm22b_dev->rx_buffer_wr++] = rfm22b_dev->rx_packet_start_afc_Hz; + // Swap the Rx packets. + if (rfm22b_dev->rx_packet_prev == NULL) + { + rfm22b_dev->rx_packet_prev = rfm22b_dev->rx_packet; + rfm22b_dev->rx_packet = rfm22b_dev->rx_packet_next; + rfm22b_dev->rx_packet_len = rfm22b_dev->rx_buffer_wr; + // Signal the receive thread. + xSemaphoreGive(rfm22b_dev->rxsem); + } + rfm22b_dev->rx_buffer_wr = 0; } // Start a new transaction @@ -1528,11 +1587,9 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->device_status = rfm22b_dev->int_status1 = rfm22b_dev->int_status2 = rfm22b_dev->ezmac_status = 0; - rx_buffer_current = 0; - rx_buffer_wr = 0; + rfm22b_dev->rx_buffer_wr = 0; rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; - rfm22b_dev->tx_packet = NULL; rfm22b_dev->frequency_hop_channel = 0; From 88be2ddf1e594d9b04312dd3deb7b0f87c5095ec Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Mon, 24 Sep 2012 20:51:34 -0700 Subject: [PATCH 470/508] RFM22B: Added a message timeout event to the RFM22B state machine that will fire if a packet takes too long to transmit / receive. --- flight/PiOS/Common/pios_rfm22b.c | 88 ++++++++++++++++++++++++++------ 1 file changed, 72 insertions(+), 16 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 723337e46..b0f321a7b 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -145,13 +145,14 @@ enum pios_rfm22b_dev_magic { enum pios_rfm22b_state { RFM22B_STATE_UNINITIALIZED, RFM22B_STATE_INITIALIZING, - RFM22B_STATE_ERROR, RFM22B_STATE_RX_MODE, RFM22B_STATE_WAIT_PREAMBLE, RFM22B_STATE_WAIT_SYNC, RFM22B_STATE_RX_DATA, RFM22B_STATE_TX_START, RFM22B_STATE_TX_DATA, + RFM22B_STATE_TIMEOUT, + RFM22B_STATE_ERROR, RFM22B_STATE_FATAL_ERROR, RFM22B_STATE_NUM_STATES // Must be last @@ -161,7 +162,6 @@ enum pios_rfm22b_event { RFM22B_EVENT_INITIALIZE, RFM22B_EVENT_INITIALIZED, RFM22B_EVENT_INT_RECEIVED, - RFM22B_EVENT_TX_MODE, RFM22B_EVENT_RX_MODE, RFM22B_EVENT_PREAMBLE_DETECTED, RFM22B_EVENT_SYNC_DETECTED, @@ -257,6 +257,10 @@ struct pios_rfm22b_dev { // afc correction reading (in Hz) int32_t afc_correction_Hz; int8_t rx_packet_start_afc_Hz; + + // The maximum time (ms) that it should take to transmit / receive a packet. + uint32_t max_packet_time; + portTickType packet_start_time; }; struct pios_rfm22b_transition { @@ -301,6 +305,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event); +static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev); @@ -346,20 +351,13 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, }, - [RFM22B_STATE_ERROR] = { - .entry_fn = rfm22_error, - .next_state = { - [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, - [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, - }, - }, [RFM22B_STATE_RX_MODE] = { .entry_fn = rfm22_setRxMode, .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE, [RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, - [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -371,7 +369,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S [RFM22B_EVENT_PREAMBLE_DETECTED] = RFM22B_STATE_WAIT_SYNC, [RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, - [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -382,6 +380,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_SYNC, [RFM22B_EVENT_SYNC_DETECTED] = RFM22B_STATE_RX_DATA, [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -390,8 +389,8 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S .entry_fn = rfm22_rxData, .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_RX_DATA, - [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, [RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -400,8 +399,8 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S .entry_fn = rfm22_txStart, .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA, - [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, [RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -410,8 +409,25 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S .entry_fn = rfm22_txData, .next_state = { [RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA, - [RFM22B_EVENT_TX_MODE] = RFM22B_STATE_TX_DATA, [RFM22B_EVENT_TX_COMPLETE] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_TIMEOUT] = { + .entry_fn = rfm22_timeout, + .next_state = { + [RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START, + [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, + [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, + [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, + }, + }, + [RFM22B_STATE_ERROR] = { + .entry_fn = rfm22_error, + .next_state = { + [RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING, [RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR, [RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR, }, @@ -569,6 +585,10 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu *rfm22b_id = (uint32_t)rfm22b_dev; g_rfm22b_dev = rfm22b_dev; + // Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet. + rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(rfm22b_dev->cfg.maxRFBandwidth) + 0.5); + rfm22b_dev->packet_start_time = 0; + // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary( rfm22b_dev->isrPending ); @@ -803,8 +823,6 @@ static void PIOS_RFM22B_Task(void *parameters) portTickType timeSinceEvent = xTaskGetTickCount() - lastEventTime; if ((timeSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) { - rfm22b_dev->resets++; - // Transsition through an error event. enum pios_rfm22b_event event = RFM22B_EVENT_ERROR; while(event != RFM22B_EVENT_NUM_EVENTS) @@ -822,6 +840,24 @@ static void PIOS_RFM22B_Task(void *parameters) event = rfm22_process_state_transition(rfm22b_dev, event); } } + + // Have we locked up sending / receiving a packet? + if (rfm22b_dev->packet_start_time > 0) + { + portTickType cur_time = xTaskGetTickCount(); + + // Did the clock wrap around? + if (cur_time < rfm22b_dev->packet_start_time) + rfm22b_dev->packet_start_time = (cur_time > 0) ? cur_time : 1; + + // Have we been sending this packet too long? + if ((cur_time - rfm22b_dev->packet_start_time) > (rfm22b_dev->max_packet_time * 5)) + { + enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); + } + } } } @@ -1165,6 +1201,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev) { + rfm22b_dev->packet_start_time = 0; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1212,6 +1249,9 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_RX_MODE; } rfm22b_dev->tx_packet = p; + rfm22b_dev->packet_start_time = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_time == 0) + rfm22b_dev->packet_start_time = 1; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1319,6 +1359,9 @@ static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22 // Valid preamble detected if (rfm22b_dev->int_status2 & RFM22_is2_ipreaval) { + rfm22b_dev->packet_start_time = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_time == 0) + rfm22b_dev->packet_start_time = 1; RX_LED_ON; return RFM22B_EVENT_PREAMBLE_DETECTED; } @@ -1452,6 +1495,7 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) } // Start a new transaction + rfm22b_dev->packet_start_time = 0; return RFM22B_EVENT_RX_COMPLETE; } @@ -1506,6 +1550,7 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->tx_packet = 0; rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; // Start a new transaction + rfm22b_dev->packet_start_time = 0; return RFM22B_EVENT_TX_COMPLETE; } @@ -1595,6 +1640,8 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->afc_correction_Hz = 0; + rfm22b_dev->packet_start_time = 0; + // **************** // read the RF chip ID bytes @@ -1781,8 +1828,17 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_INITIALIZED; } +static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev) +{ + rfm22b_dev->resets++; + rfm22b_dev->packet_start_time = 0; + return RFM22B_EVENT_TX_START; +} + static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) { + rfm22b_dev->resets++; + rfm22b_dev->packet_start_time = 0; return RFM22B_EVENT_INITIALIZE; } From 6972c29813d435b40dd56c66fc5a5f3c52a21e14 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 25 Sep 2012 18:10:15 -0700 Subject: [PATCH 471/508] RFM22B: Added check for timeout wating for sync on receive. This virtually eliminates the number of timeouts. --- flight/PiOS/Common/pios_rfm22b.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index b0f321a7b..5f95ecb39 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -835,6 +835,7 @@ static void PIOS_RFM22B_Task(void *parameters) } else { + rfm22b_dev->resets = rfm22b_dev->state; enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; while(event != RFM22B_EVENT_NUM_EVENTS) event = rfm22_process_state_transition(rfm22b_dev, event); @@ -1400,6 +1401,11 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de return RFM22B_EVENT_SYNC_DETECTED; } + else if (rfm22b_dev->int_status2 & !RFM22_is2_ipreaval) + { + // Waiting for sync timed out. + return RFM22B_EVENT_TX_START; + } return RFM22B_EVENT_NUM_EVENTS; } From dadc38d82db83f96e3166b2fe61b759514d5327b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 26 Sep 2012 01:17:32 -0500 Subject: [PATCH 472/508] Revo Mini 2: Get basic LED working. Board revision is actually 3 since right now it masquerades as Revo. --- flight/Bootloaders/RevoMini/pios_board.c | 6 ++- flight/RevoMini/System/pios_board.c | 8 +++- flight/board_hw_defs/revomini/board_hw_defs.c | 44 ++++++++++++++++++- make/boards/revomini/board-info.mk | 2 +- 4 files changed, 56 insertions(+), 4 deletions(-) diff --git a/flight/Bootloaders/RevoMini/pios_board.c b/flight/Bootloaders/RevoMini/pios_board.c index 143124ade..6587258c8 100644 --- a/flight/Bootloaders/RevoMini/pios_board.c +++ b/flight/Bootloaders/RevoMini/pios_board.c @@ -46,8 +46,12 @@ void PIOS_Board_Init() { /* Delay system */ PIOS_DELAY_Init(); + const struct pios_board_info * bdinfo = &pios_board_info_blob; + #if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); #endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_USB) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 76a81ce9f..4ca193b0b 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -296,7 +296,13 @@ void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); - PIOS_LED_Init(&pios_led_cfg); + const struct pios_board_info * bdinfo = &pios_board_info_blob; + +#if defined(PIOS_INCLUDE_LED) + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); +#endif /* PIOS_INCLUDE_LED */ /* Set up the SPI interface to the gyro/acelerometer */ if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 5516b64f0..bcdfaa7f9 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -52,9 +52,51 @@ static const struct pios_led_cfg pios_led_cfg = { .num_leds = NELEMENTS(pios_leds), }; +static const struct pios_led pios_leds_v2[] = { + [PIOS_LED_HEARTBEAT] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, + [PIOS_LED_ALARM] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + }, +}; + +static const struct pios_led_cfg pios_led_v2_cfg = { + .leds = pios_leds_v2, + .num_leds = NELEMENTS(pios_leds_v2), +}; + const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) { - return &pios_led_cfg; + switch(board_revision) { + case 2: + return &pios_led_cfg; + break; + case 3: + return &pios_led_v2_cfg; + break; + default: + PIOS_DEBUG_Assert(0); + } + return NULL; } #endif /* PIOS_INCLUDE_LED */ diff --git a/make/boards/revomini/board-info.mk b/make/boards/revomini/board-info.mk index 33fdb0591..799ffd382 100644 --- a/make/boards/revomini/board-info.mk +++ b/make/boards/revomini/board-info.mk @@ -1,5 +1,5 @@ BOARD_TYPE := 0x09 -BOARD_REVISION := 0x02 +BOARD_REVISION := 0x03 BOOTLOADER_VERSION := 0x01 HW_TYPE := 0x00 From 93c44f2a4e59b99d64699bed93fcb281b4e8f611 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 26 Sep 2012 03:02:25 -0500 Subject: [PATCH 473/508] RM2 Temporary patch: Swap the GPIO pins and the VSense pins. This needs to be based on the hardware revision later. --- flight/board_hw_defs/revomini/board_hw_defs.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index bcdfaa7f9..c2b33347a 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -402,7 +402,7 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { .maxRFBandwidth = 128000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW .slave_num = 0, - .gpio_direction = GPIO0_RX_GPIO1_TX, + .gpio_direction = GPIO0_TX_GPIO1_RX, }; #endif /* PIOS_INCLUDE_RFM22B */ @@ -1283,9 +1283,9 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { }, }, .vsense = { - .gpio = GPIOB, + .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_13, + .GPIO_Pin = GPIO_Pin_5, .GPIO_Speed = GPIO_Speed_25MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, From d2842169eed6c7842840ceff3dbaa859ac867ef5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 26 Sep 2012 04:04:48 -0500 Subject: [PATCH 474/508] Sensors: Need to support MPU6000 for revision 3 --- flight/Modules/Sensors/sensors.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 9f16fb5f9..b55d4ad2d 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -296,6 +296,7 @@ static void SensorsTask(void *parameters) #endif break; case 0x02: // MPU6000 board + case 0x03: // MPU6000 board #if defined(PIOS_INCLUDE_MPU6000) { struct pios_mpu6000_data mpu6000_data; From 26408e286fd9700b7efc07908a7bec28c7ef0e02 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 26 Sep 2012 09:44:43 -0500 Subject: [PATCH 475/508] GCS Stabilization: Force the apply button to always be there as I can't find expert mode --- .../share/openpilotgcs/default_configurations/OpenPilotGCS.xml | 2 +- .../src/plugins/config/configstabilizationwidget.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml index cab264e14..05421fc80 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml @@ -5,7 +5,7 @@ false Default configuration
Default configuration built to work on all screen sizes
- false + true en_AU true default diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 5469403ae..91b923351 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -49,8 +49,9 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); - if(!settings->useExpertMode()) + if(!settings->useExpertMode() || true) m_stabilization->saveStabilizationToRAM_6->setVisible(false); + m_stabilization->saveStabilizationToRAM_6->setVisible(true); From 6add7cc4d27c161cd525f621b8d3276156710ac9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 28 Sep 2012 01:10:46 -0500 Subject: [PATCH 476/508] Fix HMC5883 driver after Vinz' changes to PIOS_EXTI --- flight/PiOS/Common/pios_hmc5883.c | 2 +- flight/PiOS/inc/pios_hmc5883.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/Common/pios_hmc5883.c b/flight/PiOS/Common/pios_hmc5883.c index 14d4f96fe..4d43f7bd2 100644 --- a/flight/PiOS/Common/pios_hmc5883.c +++ b/flight/PiOS/Common/pios_hmc5883.c @@ -393,7 +393,7 @@ int32_t PIOS_HMC5883_Test(void) */ bool PIOS_HMC5883_IRQHandler(void) { - pios_hmc5883_data_ready = true + pios_hmc5883_data_ready = true; return false; } diff --git a/flight/PiOS/inc/pios_hmc5883.h b/flight/PiOS/inc/pios_hmc5883.h index d9c362e9d..91452028a 100644 --- a/flight/PiOS/inc/pios_hmc5883.h +++ b/flight/PiOS/inc/pios_hmc5883.h @@ -107,7 +107,7 @@ extern bool PIOS_HMC5883_NewDataAvailable(void); extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]); extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]); extern int32_t PIOS_HMC5883_Test(void); -bool void PIOS_HMC5883_IRQHandler(); +bool PIOS_HMC5883_IRQHandler(); #endif /* PIOS_HMC5883_H */ /** From 504d691487bcd83a9f91f6accc334d562eb64796 Mon Sep 17 00:00:00 2001 From: a*morale Date: Sun, 30 Sep 2012 15:44:31 +0200 Subject: [PATCH 477/508] Fixed declaration of PIOS_L3GD20_IRQHandler. --- flight/PiOS/inc/pios_l3gd20.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/PiOS/inc/pios_l3gd20.h b/flight/PiOS/inc/pios_l3gd20.h index 3a2e896fd..241f983c6 100644 --- a/flight/PiOS/inc/pios_l3gd20.h +++ b/flight/PiOS/inc/pios_l3gd20.h @@ -141,7 +141,7 @@ extern int32_t PIOS_L3GD20_SetRange(enum pios_l3gd20_range range); extern float PIOS_L3GD20_GetScale(); extern int32_t PIOS_L3GD20_ReadID(); extern uint8_t PIOS_L3GD20_Test(); -bool void PIOS_L3GD20_IRQHandler(); +extern bool PIOS_L3GD20_IRQHandler(); #endif /* PIOS_L3GD20_H */ From be752b807515fce8220a199a9e57f4ff09ca1817 Mon Sep 17 00:00:00 2001 From: a*morale Date: Sun, 30 Sep 2012 17:04:36 +0200 Subject: [PATCH 478/508] Fixed some declaration to Exti functions to make it compile. --- flight/PiOS/Common/pios_hmc5883.c | 2 +- flight/PiOS/Common/pios_rfm22b.c | 11 ++++++----- flight/PiOS/inc/pios_hmc5883.h | 2 +- flight/PiOS/inc/pios_rfm22b_priv.h | 18 +++++++++--------- 4 files changed, 17 insertions(+), 16 deletions(-) diff --git a/flight/PiOS/Common/pios_hmc5883.c b/flight/PiOS/Common/pios_hmc5883.c index 14d4f96fe..4d43f7bd2 100644 --- a/flight/PiOS/Common/pios_hmc5883.c +++ b/flight/PiOS/Common/pios_hmc5883.c @@ -393,7 +393,7 @@ int32_t PIOS_HMC5883_Test(void) */ bool PIOS_HMC5883_IRQHandler(void) { - pios_hmc5883_data_ready = true + pios_hmc5883_data_ready = true; return false; } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 5f95ecb39..2235f64e5 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -462,7 +462,7 @@ static const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x static const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 static const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 -static const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz +static const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = �AFCLimiter[7:0] x (hbsel+1) x 625 Hz static const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1 static const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0 @@ -495,7 +495,7 @@ static const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0 static const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1 static const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0 -static const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz +static const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = �AFCLimiter[7:0] x (hbsel+1) x 625 Hz static const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1 static const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2 @@ -633,13 +633,14 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu /** * The RFM22B external interrupt routine. */ -void PIOS_RFM22_EXT_Int(void) +bool PIOS_RFM22_EXT_Int(void) { if (!PIOS_RFM22B_validate(g_rfm22b_dev)) - return; + return false; // Inject an interrupt event into the state machine. PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_INT_RECEIVED, true); + return false; } /** @@ -1746,7 +1747,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // adc offset rfm22_write(RFM22_adc_sensor_amp_offset, 0); - // temp sensor calibration .. –40C to +64C 0.5C resolution + // temp sensor calibration .. �40C to +64C 0.5C resolution rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs); // temp sensor offset diff --git a/flight/PiOS/inc/pios_hmc5883.h b/flight/PiOS/inc/pios_hmc5883.h index d9c362e9d..37124e695 100644 --- a/flight/PiOS/inc/pios_hmc5883.h +++ b/flight/PiOS/inc/pios_hmc5883.h @@ -107,7 +107,7 @@ extern bool PIOS_HMC5883_NewDataAvailable(void); extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]); extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]); extern int32_t PIOS_HMC5883_Test(void); -bool void PIOS_HMC5883_IRQHandler(); +extern bool PIOS_HMC5883_IRQHandler(); #endif /* PIOS_HMC5883_H */ /** diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index cea382220..4719e722d 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -83,7 +83,7 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_is1_icrerror BIT0 // CRC Error. When set to 1 the cyclic redundancy check is failed. #define RFM22_is1_ipkvalid BIT1 // Valid Packet Received.When set to 1 a valid packet has been received. #define RFM22_is1_ipksent BIT2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted. -#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO’s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details. +#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO�s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details. #define RFM22_is1_irxffafull BIT4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller. #define RFM22_is1_ixtffaem BIT5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled. #define RFM22_is1_itxffafull BIT6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted. @@ -123,7 +123,7 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_opfc1_xton 0x01 // READY Mode (Xtal is ON). #define RFM22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State. #define RFM22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received. -#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to “unmodulated carrier” ("Register 71h. Modulation Mode Control 2"). +#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to �unmodulated carrier� ("Register 71h. Modulation Mode Control 2"). #define RFM22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal #define RFM22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires. #define RFM22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled. @@ -303,8 +303,8 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_temp_sensor_calib 0x12 // R/W #define RFM22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value. #define RFM22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable. -#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to ºC. -#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. –64C to +64C 0.5C resolution +#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to �C. +#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. �64C to +64C 0.5C resolution #define RFM22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution #define RFM22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution #define RFM22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution @@ -350,7 +350,7 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_antenna_diversity_register1 0x28 // R #define RFM22_antenna_diversity_register2 0x29 // R -#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz +#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = �AFCLimiter[7:0] x (hbsel+1) x 625 Hz #define RFM22_afc_correction_read 0x2B // R @@ -365,11 +365,11 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_dac_crc_iec16 0x02 // #define RFM22_dac_crc_biacheva 0x03 // #define RFM22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set. -#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30–4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO. +#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30�4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO. #define RFM22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled. #define RFM22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only. #define RFM22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set. -#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30–4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO. +#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30�4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO. #define RFM22_ezmac_status 0x31 // R #define RFM22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ) @@ -378,7 +378,7 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ) #define RFM22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet. #define RFM22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet. -#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one’s. May indicated Transmitter underflow in case of CRC error. +#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one�s. May indicated Transmitter underflow in case of CRC error. #define RFM22_header_control1 0x32 // R/W #define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable. @@ -580,7 +580,7 @@ typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len); // ************************************ -void PIOS_RFM22_EXT_Int(void); +bool PIOS_RFM22_EXT_Int(void); #endif /* PIOS_RFM22B_PRIV_H */ From 227aa98ebcc0a847e558afb8f0c63a482d2995c9 Mon Sep 17 00:00:00 2001 From: a*morale Date: Sun, 30 Sep 2012 20:32:03 +0200 Subject: [PATCH 479/508] Added TIM12 to PIOS_TIM --- flight/PiOS/STM32F4xx/pios_tim.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/flight/PiOS/STM32F4xx/pios_tim.c b/flight/PiOS/STM32F4xx/pios_tim.c index 7e3c6c1f6..534fa1335 100644 --- a/flight/PiOS/STM32F4xx/pios_tim.c +++ b/flight/PiOS/STM32F4xx/pios_tim.c @@ -127,6 +127,15 @@ int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg) case (uint32_t)TIM11: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM11, ENABLE); break; + case (uint32_t)TIM12: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM12, ENABLE); + break; + case (uint32_t)TIM13: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM13, ENABLE); + break; + case (uint32_t)TIM14: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM14, ENABLE); + break; #endif } @@ -486,6 +495,13 @@ static void PIOS_TIM_8_CC_irq_handler (void) PIOS_TIM_generic_irq_handler (TIM8); } +void TIM8_BRK_TIM12_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_12_irq_handler"))); +static void PIOS_TIM_12_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM12); +} + + /** * @} * @} From c2910d0ce008e6eb85c1886e6c2fb8fe9520cd5c Mon Sep 17 00:00:00 2001 From: a*morale Date: Sun, 30 Sep 2012 20:54:10 +0200 Subject: [PATCH 480/508] Receiver input working for both PPM/PWM mode for rm2 --- flight/RevoMini/System/pios_board.c | 31 ++++- flight/board_hw_defs/revomini/board_hw_defs.c | 110 +++++++++++------- 2 files changed, 95 insertions(+), 46 deletions(-) diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index 4ca193b0b..ab072eba4 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -341,10 +341,11 @@ void PIOS_Board_Init(void) { PIOS_TIM_InitClock(&tim_3_cfg); PIOS_TIM_InitClock(&tim_4_cfg); PIOS_TIM_InitClock(&tim_5_cfg); + PIOS_TIM_InitClock(&tim_8_cfg); PIOS_TIM_InitClock(&tim_9_cfg); PIOS_TIM_InitClock(&tim_10_cfg); PIOS_TIM_InitClock(&tim_11_cfg); - + PIOS_TIM_InitClock(&tim_12_cfg); /* IAP System Setup */ PIOS_IAP_Init(); uint16_t boot_count = PIOS_IAP_ReadBootCount(); @@ -356,8 +357,8 @@ void PIOS_Board_Init(void) { HwSettingsSetDefaults(HwSettingsHandle(), 0); AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); } - - + + //PIOS_IAP_Init(); #if defined(PIOS_INCLUDE_USB) @@ -470,8 +471,26 @@ void PIOS_Board_Init(void) { PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); break; case HWSETTINGS_CC_MAINPORT_SBUS: - // TODO - break; +#if defined(PIOS_INCLUDE_SBUS) + { + uint32_t pios_usart_sbus_id; + if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_id; + if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_sbus_rcvr_id; + if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; + } +#endif + break; case HWSETTINGS_CC_MAINPORT_DSM2: case HWSETTINGS_CC_MAINPORT_DSMX10BIT: case HWSETTINGS_CC_MAINPORT_DSMX11BIT: @@ -618,7 +637,7 @@ void PIOS_Board_Init(void) { } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; #endif /* PIOS_INCLUDE_GCSRCVR */ - + #ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS switch (hwsettings_rcvrport) { case HWSETTINGS_RV_RCVRPORT_DISABLED: diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index c2b33347a..d2958f2ad 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -962,17 +962,21 @@ static const struct pios_tim_clock_cfg tim_11_cfg = { }, }; -// Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_1_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, +// Set up timers that only have inputs on APB1 +// TIM2,3,4,5,6,7,12,13,14 +static const TIM_TimeBaseInitTypeDef tim_apb1_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, .TIM_CounterMode = TIM_CounterMode_Up, .TIM_Period = 0xFFFF, .TIM_RepetitionCounter = 0x0000, }; + + // Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_4_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, +// TIM1,8,9,10,11 +static const TIM_TimeBaseInitTypeDef tim_apb2_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, .TIM_CounterMode = TIM_CounterMode_Up, .TIM_Period = 0xFFFF, @@ -981,7 +985,7 @@ static const TIM_TimeBaseInitTypeDef tim_4_time_base = { static const struct pios_tim_clock_cfg tim_1_cfg = { .timer = TIM1, - .time_base_init = &tim_1_time_base, + .time_base_init = &tim_apb2_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM1_CC_IRQn, @@ -994,7 +998,7 @@ static const struct pios_tim_clock_cfg tim_1_cfg = { static const struct pios_tim_clock_cfg tim_4_cfg = { .timer = TIM4, - .time_base_init = &tim_4_time_base, + .time_base_init = &tim_apb1_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM4_IRQn, @@ -1004,6 +1008,32 @@ static const struct pios_tim_clock_cfg tim_4_cfg = { }, }, }; +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_apb2_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_12_cfg = { + .timer = TIM12, + .time_base_init = &tim_apb1_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_BRK_TIM12_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + /** * Pios servo configuration structures @@ -1133,50 +1163,50 @@ const struct pios_servo_cfg pios_servo_cfg = { #include static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { { - .timer = TIM1, + .timer = TIM12, .timer_chan = TIM_Channel_1, .pin = { - .gpio = GPIOA, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_8, + .GPIO_Pin = GPIO_Pin_14, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource8, + .pin_source = GPIO_PinSource14, }, - .remap = GPIO_AF_TIM1, + .remap = GPIO_AF_TIM12, + }, + { + .timer = TIM12, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource15, + }, + .remap = GPIO_AF_TIM12, }, { .timer = TIM8, - .timer_chan = TIM_Channel_4, + .timer_chan = TIM_Channel_1, .pin = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_9, + .GPIO_Pin = GPIO_Pin_6, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource9, - }, - .remap = GPIO_AF_TIM8, - }, - { - .timer = TIM8, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource8, + .pin_source = GPIO_PinSource6, }, .remap = GPIO_AF_TIM8, }, @@ -1198,35 +1228,35 @@ static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { }, { .timer = TIM8, - .timer_chan = TIM_Channel_1, + .timer_chan = TIM_Channel_3, .pin = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_6, + .GPIO_Pin = GPIO_Pin_8, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource6, + .pin_source = GPIO_PinSource8, }, .remap = GPIO_AF_TIM8, }, { - .timer = TIM12, - .timer_chan = TIM_Channel_2, + .timer = TIM8, + .timer_chan = TIM_Channel_4, .pin = { - .gpio = GPIOB, + .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_15, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource15, + .pin_source = GPIO_PinSource9, }, - .remap = GPIO_AF_TIM12, + .remap = GPIO_AF_TIM8, }, }; From 879dfed288b9298ab2077012cbc4eeb07c348d38 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 09:31:15 -0500 Subject: [PATCH 481/508] RM2/RM1: Make the firmware and bootloader support the pin mappings between these two targets for USB and radio A side-effect of this is the pipxsettings are no longer populated into the rfm22b cfg structure as that was made constant to be consistent with other drivers. --- flight/Bootloaders/RevoMini/pios_board.c | 2 +- flight/Modules/Radio/radio.c | 51 ++++++++------ flight/RevoMini/System/pios_board.c | 2 +- flight/board_hw_defs/revomini/board_hw_defs.c | 67 ++++++++++++++++++- 4 files changed, 99 insertions(+), 23 deletions(-) diff --git a/flight/Bootloaders/RevoMini/pios_board.c b/flight/Bootloaders/RevoMini/pios_board.c index 6587258c8..e6152f687 100644 --- a/flight/Bootloaders/RevoMini/pios_board.c +++ b/flight/Bootloaders/RevoMini/pios_board.c @@ -62,7 +62,7 @@ void PIOS_Board_Init() { PIOS_USB_DESC_HID_ONLY_Init(); uint32_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) uint32_t pios_usb_hid_id; diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 41e732215..01fd7bb2b 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -28,6 +28,8 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include +#include #include #include #include @@ -120,8 +122,11 @@ static RadioData *data = 0; uint32_t pios_rfm22b_id = 0; uint32_t pios_com_rfm22b_id = 0; uint32_t pios_packet_handler = 0; -extern struct pios_rfm22b_cfg pios_rfm22b_cfg; +const struct pios_rfm22b_cfg *pios_rfm22b_cfg; +// *************** +// External functions +extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); /** * Start the module @@ -177,62 +182,70 @@ static int32_t RadioInitialize(void) PipXSettingsGet(&pipxSettings); /* Retrieve hardware settings. */ - pios_rfm22b_cfg.frequencyHz = pipxSettings.Frequency; - pios_rfm22b_cfg.RFXtalCap = pipxSettings.FrequencyCalibration; + const struct pios_board_info * bdinfo = &pios_board_info_blob; + pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + + // Not appropriate for a constant struct. Is it necessary to make a local copy of the cfg? + // We should probably be consistent with other drivers and allocate a device structure with + // dynamical configuration in it +#if 0 + pios_rfm22b_cfg->frequencyHz = pipxSettings.Frequency; + pios_rfm22b_cfg->RFXtalCap = pipxSettings.FrequencyCalibration; switch (pipxSettings.RFSpeed) { case PIPXSETTINGS_RFSPEED_2400: - pios_rfm22b_cfg.maxRFBandwidth = 2000; + pios_rfm22b_cfg->maxRFBandwidth = 2000; break; case PIPXSETTINGS_RFSPEED_4800: - pios_rfm22b_cfg.maxRFBandwidth = 4000; + pios_rfm22b_cfg->maxRFBandwidth = 4000; break; case PIPXSETTINGS_RFSPEED_9600: - pios_rfm22b_cfg.maxRFBandwidth = 9600; + pios_rfm22b_cfg->maxRFBandwidth = 9600; break; case PIPXSETTINGS_RFSPEED_19200: - pios_rfm22b_cfg.maxRFBandwidth = 19200; + pios_rfm22b_cfg->maxRFBandwidth = 19200; break; case PIPXSETTINGS_RFSPEED_38400: - pios_rfm22b_cfg.maxRFBandwidth = 32000; + pios_rfm22b_cfg->maxRFBandwidth = 32000; break; case PIPXSETTINGS_RFSPEED_57600: - pios_rfm22b_cfg.maxRFBandwidth = 64000; + pios_rfm22b_cfg->maxRFBandwidth = 64000; break; case PIPXSETTINGS_RFSPEED_115200: - pios_rfm22b_cfg.maxRFBandwidth = 128000; + pios_rfm22b_cfg->maxRFBandwidth = 128000; break; } switch (pipxSettings.MaxRFPower) { case PIPXSETTINGS_MAXRFPOWER_125: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_0; break; case PIPXSETTINGS_MAXRFPOWER_16: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_1; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_1; break; case PIPXSETTINGS_MAXRFPOWER_316: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_2; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_2; break; case PIPXSETTINGS_MAXRFPOWER_63: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_3; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_3; break; case PIPXSETTINGS_MAXRFPOWER_126: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_4; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_4; break; case PIPXSETTINGS_MAXRFPOWER_25: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_5; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_5; break; case PIPXSETTINGS_MAXRFPOWER_50: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_6; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_6; break; case PIPXSETTINGS_MAXRFPOWER_100: - pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_7; + pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_7; break; } +#endif /* Initalize the RFM22B radio COM device. */ - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg.slave_num, &pios_rfm22b_cfg)) + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) return -1; // Initialize the packet handler diff --git a/flight/RevoMini/System/pios_board.c b/flight/RevoMini/System/pios_board.c index ab072eba4..cc227706a 100644 --- a/flight/RevoMini/System/pios_board.c +++ b/flight/RevoMini/System/pios_board.c @@ -383,7 +383,7 @@ void PIOS_Board_Init(void) { #endif uint32_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_USB_CDC) diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index d2958f2ad..8785d192f 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -392,7 +392,20 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { }, }; -struct pios_rfm22b_cfg pios_rfm22b_cfg = { +const struct pios_rfm22b_cfg pios_rfm22b_rm1_cfg = { + .spi_cfg = &pios_spi_telem_flash_cfg, + .exti_cfg = &pios_exti_rfm22b_cfg, + .frequencyHz = 434000000, + .minFrequencyHz = 434000000 - 2000000, + .maxFrequencyHz = 434000000 + 2000000, + .RFXtalCap = 0x7f, + .maxRFBandwidth = 128000, + .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW + .slave_num = 0, + .gpio_direction = GPIO0_RX_GPIO1_TX, +}; + +const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = { .spi_cfg = &pios_spi_telem_flash_cfg, .exti_cfg = &pios_exti_rfm22b_cfg, .frequencyHz = 434000000, @@ -405,6 +418,21 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { .gpio_direction = GPIO0_TX_GPIO1_RX, }; +const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision) +{ + switch(board_revision) { + case 2: + return &pios_rfm22b_rm1_cfg; + break; + case 3: + return &pios_rfm22b_rm2_cfg; + break; + default: + PIOS_DEBUG_Assert(0); + } + return NULL; +} + #endif /* PIOS_INCLUDE_RFM22B */ #endif /* PIOS_INCLUDE_SPI */ @@ -1303,7 +1331,27 @@ static const struct pios_ppm_cfg pios_ppm_cfg = { #if defined(PIOS_INCLUDE_USB) #include "pios_usb_priv.h" -static const struct pios_usb_cfg pios_usb_main_cfg = { +static const struct pios_usb_cfg pios_usb_main_rm1_cfg = { + .irq = { + .init = { + .NVIC_IRQChannel = OTG_FS_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 3, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .vsense = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_25MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + }, + } +}; + +static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { .irq = { .init = { .NVIC_IRQChannel = OTG_FS_IRQn, @@ -1323,6 +1371,21 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { } }; +const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) +{ + switch(board_revision) { + case 2: + return &pios_usb_main_rm1_cfg; + break; + case 3: + return &pios_usb_main_rm2_cfg; + break; + default: + PIOS_DEBUG_Assert(0); + } + return NULL; +} + #include "pios_usb_board_data_priv.h" #include "pios_usb_desc_hid_cdc_priv.h" #include "pios_usb_desc_hid_only_priv.h" From 71e1a14e93ccf247937714cda1c59d0ab0cc017a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 09:37:55 -0500 Subject: [PATCH 482/508] GCS Uploader: Add a backward compatibility condition for RM1 using RM2 firmware --- ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index c944f9a37..b3cb197bb 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -353,7 +353,9 @@ void deviceWidget::uploadFirmware() int board = m_dfu->devices[deviceID].ID; int firmwareBoard = ((desc.at(12)&0xff)<<8) + (desc.at(13)&0xff); if((board == 0x401 && firmwareBoard == 0x402) || - (board == 0x901 && firmwareBoard == 0x902)) { + (board == 0x901 && firmwareBoard == 0x902) || // L3GD20 revo supports Revolution firmware + (board == 0x902 && firmwareBoard == 0x903)) // RevoMini1 supporetd by RevoMini2 firmware + { // These firmwares are designed to be backwards compatible } else if (firmwareBoard != board) { status("Error: firmware does not match board", STATUSICON_FAIL); From 0c8c148b51626da1e860cd800b6a1a144a2d3d3c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 10:07:50 -0500 Subject: [PATCH 483/508] PipX HW Def: Use PIOS_BOARD_HW_DEFS_GetRfm22Cfg since the radio module initializes the modem and doesn't know teh difference between RM2 and PipX --- flight/board_hw_defs/pipxtreme/board_hw_defs.c | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index 16ff720c1..e436f3975 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -219,7 +219,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { #include -struct pios_rfm22b_cfg pios_rfm22b_cfg = { +struct pios_rfm22b_cfg pios_rfm22b_pipx_cfg = { .spi_cfg = &pios_spi_rfm22b_cfg, .exti_cfg = &pios_exti_rfm22b_cfg, .frequencyHz = 434000000, @@ -232,6 +232,12 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = { .gpio_direction = GPIO0_TX_GPIO1_RX, }; +//! Compatibility layer for various hardware revisions +const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision) +{ + return &pios_rfm22b_pipx_cfg; +} + #endif /* PIOS_INCLUDE_RFM22B */ #if defined(PIOS_INCLUDE_ADC) From a8590045a8a4c2604c909f7365b3d971493460bd Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 2 Oct 2012 19:52:21 -0700 Subject: [PATCH 484/508] RFM22B: Moved radio status reporting from the radio module into the rfm22b driver task. --- flight/Modules/Radio/radio.c | 23 ------ flight/PiOS/Common/pios_rfm22b.c | 135 +++++++++++++++++-------------- 2 files changed, 76 insertions(+), 82 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 01fd7bb2b..b5beb1359 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -408,8 +408,6 @@ static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) */ static void radioStatusTask(void *parameters) { - PHStatusPacket status_packet; - while (1) { PipXStatusData pipxStatus; uint32_t pairID; @@ -468,27 +466,6 @@ static void radioStatusTask(void *parameters) // Update the object PipXStatusSet(&pipxStatus); - // Broadcast the status. - { - static uint16_t cntr = 0; - if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS) - { - // Queue the status message - status_packet.header.destination_id = 0xffffffff; - status_packet.header.type = PACKET_TYPE_STATUS; - status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet); - status_packet.header.source_id = pipxStatus.DeviceID; - status_packet.retries = data->comTxRetries; - status_packet.errors = data->packetErrors; - status_packet.uavtalk_errors = data->UAVTalkErrors; - status_packet.dropped = data->droppedPackets; - status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id); - PHPacketHandle sph = (PHPacketHandle)&status_packet; - PHTransmitPacket(PIOS_PACKET_HANDLER, sph); - cntr = 0; - } - } - vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); } } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 2235f64e5..76f02e1de 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -54,6 +54,7 @@ #include #include #include +#include /* Local Defines */ #define STACK_SIZE_BYTES 200 @@ -62,11 +63,12 @@ #define EVENT_QUEUE_SIZE 5 #define PACKET_QUEUE_SIZE 3 -// RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). -// A 256 byte message at 56kbps should take less than 40ms -// Note: This timeout should be rate dependent. +// The maximum amount of time without activity before initiating a reset. #define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms +// The time between updates over the radio link. +#define RADIOSTATS_UPDATE_PERIOD_MS 250 + // this is too adjust the RF module so that it is on frequency #define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default #define OSC_LOAD_CAP_1 0x7D // board 1 @@ -94,28 +96,6 @@ #define SYNC_BYTE_3 0x4B // #define SYNC_BYTE_4 0x59 // -// ************************************ -// the default RF datarate - -//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec -#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING - -// ************************************ - -#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps - #ifndef RX_LED_ON #define RX_LED_ON #define RX_LED_OFF @@ -258,9 +238,12 @@ struct pios_rfm22b_dev { int32_t afc_correction_Hz; int8_t rx_packet_start_afc_Hz; + // The status packet + PHStatusPacket status_packet; + // The maximum time (ms) that it should take to transmit / receive a packet. uint32_t max_packet_time; - portTickType packet_start_time; + portTickType packet_start_ticks; }; struct pios_rfm22b_transition { @@ -308,6 +291,7 @@ static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_ static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev); +static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev); // SPI read/write functions static void rfm22_assertCs(); @@ -587,7 +571,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet. rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(rfm22b_dev->cfg.maxRFBandwidth) + 0.5); - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary( rfm22b_dev->isrPending ); @@ -791,7 +775,8 @@ static void PIOS_RFM22B_Task(void *parameters) struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters; if (!PIOS_RFM22B_validate(rfm22b_dev)) return; - static portTickType lastEventTime; + portTickType lastEventTicks = xTaskGetTickCount(); + portTickType lastStatusTicks = lastEventTicks; while(1) { @@ -803,7 +788,7 @@ static void PIOS_RFM22B_Task(void *parameters) // Wait for a signal indicating an external interrupt or a pending send/receive request. if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { rfm22b_dev->irqs_processed++; - lastEventTime = xTaskGetTickCount(); + lastEventTicks = xTaskGetTickCount(); // Process events through the state machine. enum pios_rfm22b_event event; @@ -821,8 +806,11 @@ static void PIOS_RFM22B_Task(void *parameters) else { // Has it been too long since the last event? - portTickType timeSinceEvent = xTaskGetTickCount() - lastEventTime; - if ((timeSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) + portTickType curTicks = xTaskGetTickCount(); + if (curTicks < lastEventTicks) + lastEventTicks = curTicks; + portTickType ticksSinceEvent = curTicks - lastEventTicks; + if ((ticksSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) { // Transsition through an error event. enum pios_rfm22b_event event = RFM22B_EVENT_ERROR; @@ -832,34 +820,36 @@ static void PIOS_RFM22B_Task(void *parameters) // Clear the event queue. while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) ; - lastEventTime = xTaskGetTickCount(); - } - else - { - rfm22b_dev->resets = rfm22b_dev->state; - enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; - while(event != RFM22B_EVENT_NUM_EVENTS) - event = rfm22_process_state_transition(rfm22b_dev, event); + lastEventTicks = xTaskGetTickCount(); } } // Have we locked up sending / receiving a packet? - if (rfm22b_dev->packet_start_time > 0) + if (rfm22b_dev->packet_start_ticks > 0) { - portTickType cur_time = xTaskGetTickCount(); + portTickType cur_ticks = xTaskGetTickCount(); // Did the clock wrap around? - if (cur_time < rfm22b_dev->packet_start_time) - rfm22b_dev->packet_start_time = (cur_time > 0) ? cur_time : 1; + if (cur_ticks < rfm22b_dev->packet_start_ticks) + rfm22b_dev->packet_start_ticks = (cur_ticks > 0) ? cur_ticks : 1; // Have we been sending this packet too long? - if ((cur_time - rfm22b_dev->packet_start_time) > (rfm22b_dev->max_packet_time * 5)) + if (((cur_ticks - rfm22b_dev->packet_start_ticks) / portTICK_RATE_MS) > (rfm22b_dev->max_packet_time * 3)) { enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; while(event != RFM22B_EVENT_NUM_EVENTS) event = rfm22_process_state_transition(rfm22b_dev, event); } } + + // Queue up a status packet if it's time. + portTickType curTicks = xTaskGetTickCount(); + // Rollover + if (curTicks < lastStatusTicks) + lastStatusTicks = curTicks; + if (((curTicks - lastStatusTicks) / portTICK_RATE_MS) > RADIOSTATS_UPDATE_PERIOD_MS) + if (rfm22_sendStatus(rfm22b_dev)) + lastStatusTicks = curTicks; } } @@ -1203,7 +1193,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev) { - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1251,9 +1241,9 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_RX_MODE; } rfm22b_dev->tx_packet = p; - rfm22b_dev->packet_start_time = xTaskGetTickCount(); - if (rfm22b_dev->packet_start_time == 0) - rfm22b_dev->packet_start_time = 1; + rfm22b_dev->packet_start_ticks = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_ticks == 0) + rfm22b_dev->packet_start_ticks = 1; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1316,6 +1306,36 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_TX_STARTED; } +static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev) +{ + PHPacketHandle sph = (PHPacketHandle)&(rfm22b_dev->status_packet); + + // Queue the status message + rfm22b_dev->status_packet.header.source_id = rfm22b_dev->deviceID; + rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast + rfm22b_dev->status_packet.header.type = PACKET_TYPE_STATUS; + rfm22b_dev->status_packet.header.data_size = PH_STATUS_DATA_SIZE(&(rfm22b_dev->status_packet)); + rfm22b_dev->status_packet.header.tx_seq = 0; + rfm22b_dev->status_packet.header.rx_seq = 0; + rfm22b_dev->status_packet.errors = rfm22b_dev->errors; + rfm22b_dev->status_packet.resets = rfm22b_dev->resets; + rfm22b_dev->status_packet.retries = 0; + rfm22b_dev->status_packet.uavtalk_errors = 0; + rfm22b_dev->status_packet.dropped = 0; + + // Add the error correcting code. + encode_data((unsigned char*)sph, PHPacketSize(sph), (unsigned char*)sph); + if (xQueueSend(rfm22b_dev->packetQueue, &sph, 0) != pdTRUE) + return false; + + // Process a SEND_PACKT event. + enum pios_rfm22b_event event = RFM22B_EVENT_SEND_PACKET; + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); + + return true; +} + // ************************************ /** @@ -1361,9 +1381,9 @@ static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22 // Valid preamble detected if (rfm22b_dev->int_status2 & RFM22_is2_ipreaval) { - rfm22b_dev->packet_start_time = xTaskGetTickCount(); - if (rfm22b_dev->packet_start_time == 0) - rfm22b_dev->packet_start_time = 1; + rfm22b_dev->packet_start_ticks = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_ticks == 0) + rfm22b_dev->packet_start_ticks = 1; RX_LED_ON; return RFM22B_EVENT_PREAMBLE_DETECTED; } @@ -1502,7 +1522,7 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) } // Start a new transaction - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_RX_COMPLETE; } @@ -1557,7 +1577,7 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->tx_packet = 0; rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; // Start a new transaction - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_TX_COMPLETE; } @@ -1647,7 +1667,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->afc_correction_Hz = 0; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // **************** // read the RF chip ID bytes @@ -1731,9 +1751,6 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) if (freq_hop_step_size > 255) freq_hop_step_size = 255; rfm22b_dev->frequency_hop_step_size_reg = freq_hop_step_size; - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, true); - // FIFO mode, GFSK modulation uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); @@ -1838,14 +1855,14 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev) { rfm22b_dev->resets++; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_TX_START; } static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) { rfm22b_dev->resets++; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_INITIALIZE; } From 3cdb9df05f84e9b3fc7bf22e3d380ec7b988ef1f Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 2 Oct 2012 20:59:43 -0700 Subject: [PATCH 485/508] RFM22B: Removed setting register 0x58 in the rfm22_setDatarate call, which was breaking all data rates < 100000 bps. Also temporatily fixed the datarate at 64kbps. --- flight/PiOS/Common/pios_rfm22b.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 76f02e1de..96d735d61 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1127,6 +1127,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) int lookup_index = 0; while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) lookup_index++; + lookup_index = 10; datarate_bps = data_rate[lookup_index]; @@ -1156,12 +1157,14 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) // rfm22_afc_limiter rfm22_write(0x2A, reg_2A[lookup_index]); +/* This breaks all bit rates < 100000! if (datarate_bps < 100000) // rfm22_chargepump_current_trimming_override rfm22_write(0x58, 0x80); else // rfm22_chargepump_current_trimming_override rfm22_write(0x58, 0xC0); +*/ // rfm22_tx_data_rate1 rfm22_write(0x6E, reg_6E[lookup_index]); @@ -1570,7 +1573,7 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) } // Packet has been sent - if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) + else if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) { // Free the tx packet PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet); From ab291ae1e4c0d448d77a85635e2e306665a55f61 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 21:41:28 -0500 Subject: [PATCH 486/508] Android USB: Only attempt to open validate devices. --- .../src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java index ab170ff48..ae406121d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java @@ -123,7 +123,10 @@ public class HidUAVTalk extends TelemetryTask { while(deviceIterator.hasNext()){ UsbDevice dev = deviceIterator.next(); if (DEBUG) Log.d(TAG, "Testing device: " + dev); - usbManager.requestPermission(dev, permissionIntent); + if( ValidateFoundDevice(dev) ) { + usbManager.requestPermission(dev, permissionIntent); + break; + } } if (DEBUG) Log.d(TAG, "Registered the deviceAttachedFilter"); From 955c030c0f122bdb5d9227528feee49a449fe96e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 23:36:49 -0500 Subject: [PATCH 487/508] Android Telemetry: Start the service explicitly before binding. This ensures it continues running while the tablet rotates or changes activities. --- .../src/org/openpilot/androidgcs/ObjectManagerActivity.java | 1 + .../org/openpilot/androidgcs/telemetry/BluetoothUAVTalk.java | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 8cd89e8d8..42915413b 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -256,6 +256,7 @@ public abstract class ObjectManagerActivity extends Activity { // Bind to the telemetry service (which will start it) Intent intent = new Intent(getApplicationContext(), org.openpilot.androidgcs.telemetry.OPTelemetryService.class); + startService(intent); if (DEBUG) Log.d(TAG, "Attempting to bind: " + intent); bindService(intent, mConnection, Context.BIND_AUTO_CREATE); diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/BluetoothUAVTalk.java index 5c1028cb3..257f94145 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/BluetoothUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/BluetoothUAVTalk.java @@ -143,7 +143,7 @@ public class BluetoothUAVTalk extends TelemetryTask { socket = null; try { - socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + socket = device.createRfcommSocketToServiceRecord(MY_UUID); } catch (IOException e) { if (ERROR) Log.e(TAG,"Unable to create Rfcomm socket"); return false; From 94c5b30e6890b87bf9d7044c928059e88164320a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 2 Oct 2012 23:58:21 -0500 Subject: [PATCH 488/508] Android: Make the icon smaller so the USB permission dialog works. --- androidgcs/res/drawable-hdpi/ic_logo.png | Bin 48558 -> 25295 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/androidgcs/res/drawable-hdpi/ic_logo.png b/androidgcs/res/drawable-hdpi/ic_logo.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..1f3d2de59c1f04347a6758b24f4a4cdccc1c5f1d 100644 GIT binary patch literal 25295 zcmX7vWmp@}*M<{SWgyNA-T7|?CG#?bgqyALsKn$BH$SeAg-+%jgtVH~C zf1ZtDOGGfTlmcaGzoAUsCr}Xi2`IS$!ci2X#X`35S-64Ky@!OemAzN=+3UrjWjaRE zS#R~UV21P>T|W#7uL|#q?wTygzB9F}&m_}{NG-3-9%D%PR!p3nqZ&0?JFN_wF5g$< zOdJ})=jtN59X(v9ib5SaPCR*0yP@y&j{Y|hNv96`Ohn~Jc894sJZ;~gOxTI?cxTs$ z{O^+TY)SwTp&TL2?>qjNiGJpHYP1q)apP=5O^j!r3{jK#0anM>lR!g z%dA#rzoJ(k=jJm!CZItfu=Nm}6fd^7mpH-}8$@os8$Ir@w|9SXxr|+ocI+3Z{@mBl zeK%kAoAb$03qjP(J1X_Z;F)JP+827NcSgV|Myx}pHU05Lt;OF3KM(E$$LX26BnHHX zC!5#D%U<$dNs<*wgC_sn3N(vir8B;0!1 zp36AzQ)OySupDJs963}N2Y5HKMO<{{uF&1H#z&0(kyo+v-=r0)Atypas#hPW_LVo5-5V#qKyP)% zm}Nz&1<7A41<6HC>0XH^K3+=b16;m1P_Prg!v>nOqP`mdK-lx&0VHx(l?DJL0q&L2|!xPn3)?e2OVbw;oRG zZDa87BW}$PvXF|6!XhHVLzL1kyj>b<^gsOPu|Rq9?)C_BE9@nYv-{7u=$HPXgnflR zFJy9Y@qi;mF=_RuYej~A>ru^+|Aj}8FVj#(qN`uYQ)P0zdJaMk!XLRn} z^>`!8ubZrEtQs+dwu$of4eK&r_4PCC9qov83btJ*#QoKRvDgW55lOYDNJTx5PLcSy z5F8o!2e(~wwsCUBki?K$h>!pYOm;3vy5VNsv2MGg&s>B6F{SM+oEJ>K*l5`yTVfb2 zr*w_%@+fwwiJ(lsjKoF z6*s7zawO6I*R>!*4F`Z2B0E#Q@ptH@4A&a!c^)1^%Ih(_A7+HO5iE8H>k%_ zlJ<4#|1V&Xhmt*&I7|sOcn_MM!8?COh^m!`#m?5AidPu*zxEOck;I%C9fvv@E4er4@HS99N411_}^tPkU|3aOXGiMX%U{m5(zV&Wd0i*Qs`gSP_=qq z|9dxzQ3wvxo8O8hr#k^%A==c*cEuCcnzE zcZ_CUI;}spEDd-JK+l4=j^6ruq3cr@6%~c9XJ~jx{MO{xDhLJJ-S6>6hep5CzumCb zI@aFS)>%hK=kq`UZKc=giZ_n)`X*#u3;HbNP9N9p7*zGOk~J@De(;5}2IXfK*gPmp z$R(dZ-1YhK*6W@3m4-7w5BiOW25)=Cqau|R3y@2Qb2DO zZ}Uml)zBrm!UNxtu5fZ%T5Dz|`LmJl`JWRg2-`Ur8OzlO1%Qb-t~fjg6mt02G~xHK zU##Xii)LlE`P~$$x(+O5UQ%`fU*hsp#ig}44s7Fl`v<@8yjbr|N7;=`h4QG ze0RR7V`=Mjfm4Z1FhM27P_G-(4n97h8Y0+TUzg`Ybv!lm*7y+hZtO z3#3P*yH~KXZ)zYT@Fh+&_RLuFyIs~fgbH}R#miP9SSJI7;LtEothU%q6*aR$ikdVF zeQ)MCr!VI2 zsCMihZ8+ryw#XjM3}OvqZ|Yk>H^-3p<52-Q3h&!s6dc{$s9PV|V5IgwyjcGT2TlfZ znPT<+Sc+ota3fT%MHF7H=Z9;^)V6}eLn3nGg0{0&~t+fI?-P>Hf|@%R0R(lY`X(g-{?a zWgSOy>sk=TzfcmBy%oP(;|iQ}M)B<&_*8OLzYJo*GiQ9t3bnWFi}~x54df;s0TPtFc&hQL@1-8}Q)(m)40#n_u=o$dp=e>e>LZS3!+s~gyo8##< zvTt&cu|4WN(8<$`Tq8x{ABJxwSR^gw9%=QscW?s-hf<&6Gp&sy!k{?CFIGFdSlvCZ z_jbdl6P>03wORz1XsQka7~ytIArA3s46yJIeD)s=7!0ofe`-Y3#5+LE~qih6}GrA_`rV%wIdYHS!@4`h5FvazMoNP$otOLdzRBD?sLPiWHbOcBf);^oewir zpXyj2!*Kcfq=j>N6yWbUqu`_FR>+y-e6>_?N0@^I!=$y60%Gxt%EE>4)ws+u|C~{Q zW^ptz=LMvJ3XkKD{Tm@I2BY5{eVFL2NtQ*<-+>4pY|$zrwGAQVkcKo9?^4m1yG;Ltt=(U&gO7yBR$MxrH zSfa>r)QM_HG%4yZ;cN+jvgn4y)zS{+*yS>~BYAY%6=jMY(QT*H>W8iXRR8UK#dc7P z2QK0RVi$o6#IY!fcx|)laU2giUmrV{g?GOfKpM6-iyeA2ri5`Q*Y|Yl)akY7UycM! zI4N!cUs$O6UBWL@yEuh zHD*IZ6tM`MF5e8XuQja?2jw2|kWr6w3VLP*4;;$B6Qz5(Jg>+@dp^>BIfvzhi&kJEDPY4jD1M>Rhe->d0{ylS^>KG=cc}_`n(=aeS;$HA!SD0 zyNVRp(&LEuP1UC_j_NQBo2u-SFV~`D9`M7zfY;}f`Z*Jb8=Cpf7sP`e4pizm1z6ia zUy$hHSPTaCp@4M_N&k6U#0_edZR@CrF(n9Mj z5W<`D3yMts=U=m%$JsskgkP zehDP^`3u_7Zt1a!rBg$^rn+FxBC?{p4#jOJ9LiFSiii~{vpd|*bL!V~>XxR8Qf@Z| zF;7{xkT=yE5&f%AJAxvM1?FZvGRbAd2 zp$H%jEEe>mgnDfo$RKYApAKtH2%|mI?jd;m%ajEf_CKN)bW%>Ty;fZsUpftq z>toK+(a%33fNcRG;g-@szH~lRfyX?$f2ghkbvT27roMRUs_RV}hl75;%6mf*2SdT; zy}*JjcXyi+tF2vBM1j|l8@%`~5t@*N*w2W%Qp#G zn37WY7KFBdEKn*Y&X;F1`LJ;Mm#O>`jRB$POG!c8WCmu4P!>$809SxGeZ5NZ4suSW zp}r#X^}1F!ki!Pk8P_@%LU?9Y zI4WTK;blzhGDfYI$Ge!<0;L`Yw%5FyV?QVEd}Xcmn0Jzl!V;Ur{|+(6$+c^vg{tC>(c!-w}TpH>;_wDyDDy_c;kG`&pqQ9#%p9*KhU{(aYa?BGRe~c2cUlCL58O%; z@IcHqZA)#W&V1fsN1YDF5j%sbt>^oJV?W*UP6!NvrjSOE&+>-h38dDLMJn6!O`%M* zQF|7hb6&n+YfXnGBG|iWN2dzIpX1wV%Edlw!S9mmnAydst8_ZOkOXw)<QZRpZWeHk9KXZ->s@L+%ajIfKbDelDN!`Y2>A1AZ|kXFSn5 z7QACKXUgOPh4@+C_h)Wki%c^HZ^3LI0Mh8Z=xJN+&_Z(cwno5W=)H{DLJS$N`$KX@ znu9Gh6h)l;=4S1Qtd0emSQEAE{vJyRtZqPVq+exTId-z!VzN2v`Ln%00_NyEl4at? z$)7(d_%==Mu^mx%s{nyD2#vXSoPk5#>iB+SCt|+0{)*=LoV3=LN249@ zc=45#+XbmQbWP2ygKb0k5%C`5F)D1g6q$G;p1PKzkMTp>)_MlQiiqma8n|qRY~wUR zA1BnU`dvtq?A=mcpd5yC+j$?w=Y#1|)<;2n?qE9-A)X1uaR;FTAeh!6JDGI^-J9%# z%NHUHM3>o(JJmTv<>@|_f67=wA)s-tOu-Sa*zy&x6d9(Lj@ImL?_>AO^2K!qJ?=X* zJuQA|s8y`}!dVgEuMM3F0F5d34s%=u?7_FKK(DF5yrVdU%&oAJ_7Ew|b0Au|>Oa@y zPtdXHjk#a9o^Bu&6)6swW9W(cv(-9M(2BR!$k zFs~wC>RF}>`Uvc)(4Jo}&!++GA0|#L_>8p>u^GeJiB^%_5 zT&_5fAab)xWIyKZyIwhN<#x0Br)Rtk`)xoCpx#g9-e>WXf3#s`*~5zSWK8L3Fi(CUu?Mf z(hS>)zcrB~_q(}OD!Hn_u%IpVE#`?dc+Cf}KxH|;f{oorr;1$r z^)rhpt|Sz!l03|C99fn0$wB|g4nMi6hag*Oi;iD@I+-=G+V4c@v0+^+B(@YB#x{k+ zA>)$KvXQQlerCvYGk3AF_g)@jbvQ7K!DQCY_ZQnDS+d5q0ZhKsTc9t12%(&e9b^uP zr!yI2Lm9F^2|NJG1Yk-KDO5{u(G3O7<4f-hS0-0yI6Cy`Na+uyW+z}O6}7~-ATk-F zTKlu;=ryH(!l91euR~4FqVDm(8xSha_?f8cMqvZP#V7g$+dmQ(zv-y}Xyh78ztohU zEr9uqJdeDy*DKFH7I8+04@a&o(792qZJttj<19%K;X2IXaMTGzRfjQQpoGM5m^$pN zYX4GUfZ`Y@%>#x09uwNc)cMIv3pTFDx`$RN>O zvF^S#=R-~i$0W=5$60)uHFVl1{LBqi2!r;_7pXob?7t7G@jMx+EVXVgCvA#mKYgc- zh@L`a?nK~=SEHMejrWC^T2Vctf|Ttg@qB|?c>4O6xCvj6qc109)91%_U0@F53y zpgebA&tk_t#o8x>+aF8dLvrpdl=|g8z?MK~Qmv_woPLqo)+T%me$D<0kd0ZW)x^6{ zSo+Y;*3go&n%sZw%NRm(h5*k!ZNktxQ5I2X($K&^W1%Q7aqTyY%BpnV>ky-fM7~&& z3Yi599Lpe*9~Ye0vQ~Qjy`-z_k$aqf&mXIc_xYnXEyt_frzv@dzWl=c#=AG38sYY1 zRLtxN+Q-iM>?A0K>{JXLcoR$l!!!Gk*fm1jPYY*(0F8{p=F8VavkH6T)#c9Zvaq9{ zfK6x5BJ;RjwuS3XwvcU|%9mO_qvOX{Jqxk)!9SQ$^3t{oa~tro4`OW{GQwnQTaH9s z{kR(dUR{REAqUB^L2KzZfi%25h|ucU&*r? zz8{Xd5br@$lpna-{XzG-VM}DHxVd=0Ve8k=?<)Wq+IzRoGw0Tecc9QkC|zr7H$Tlp z`uoX}%=*-H#-dld)byoDV9fbC8O7`i&g8S+1(F7#^OQG1$_6f1&7*QY73k3iP z*M|}*o9uU~@rTnGyDX#1;{R2+eHmtbw0r*)>@^I2evn$Jf2Tbra>z0AEjIEjkg%+W z4})BR(&OAO0ypi3leGZy8gmxLbU5uAC-wPp0^akCj5j&3ID3aF@4-$Jr@AFK=f zvXn7jqaOhHcjD{ z@X#PfGO_dJpR*7LvuHp zI18E&DnKJ>c>=!4ASL4lL$5;uUQ^vEVx-$$h9UQHdF4$(@m40HlDR<$-5W{iYq>1g z{^Cw&gs_R*bfFoy7FLQ&DWvD%mSMg^o{!#T)|2)Ql{ZefyW?%s8G=_2mf&6lA_UI~ zMvl)Hs=}B$!MnlO`cri}?N|&#Xr?Lv&@8`LsTU3CQ$~&Z9Q_dp; zErRDFB2%KzA+a7* zvh-!JP=r}dhsH6e z-&$l5g|GN60H+S;iOQBQRGQ?0s~?7EMq(WImUdT1#`rm@)%dw)VdIICu_IpdA^|no z7O&atKr(jniFNWV?|V)U`+s2z0U7`f*2Izp#3JoQIq%+w~x&mT8t&v#FFCrL^6!2Jgw3Iu7f2_vgs6@pjey()7OWz z8{l(L0D}3he_7igaGs-^p60FTZ%(TE)^huM5H=s8_N>6Fg7QdsrS*y`zUT}jxO>nW z6V;YF12WS}r+9FC?xg*fW32V_l&A#pkn)po$S||wj$1lhXKEb_oFKCy%kd?R92kAR zSyBf@&X*ulBN>2B!(7VF#U`TRMMX{JhE=a}$^rqOUAZBEs$A~eY5dI~2g6!5G7uLa z3N+@(g-Zsv9!MOED0NuM>U)woDvvey+%JSr2BAq8sFXnb`aw+8Ea2akxCflmUbpdpUb zW4z_kh=*7EQ$OE6zMsk$-XtviDhs98V4M(F8e;t3W>H;k=$ut(PE9Np@TN$NqQVIAQhuZ0*_fh~LrP+tn z&zm6g43ToMxmX?ENk0fRbA(QKBM~c-+sEuFZV)Xsr`>%Z+Cc^%n$-8Szh1$K9h(j(r{uOFjCq?>8^X4}BnNwG6 zUst@P)9`jDm!bO8w>xS%q3LxNX)?TRnNX>GLy9?n8uL@9!{pirC;TfG1HfoQw%3Y& za7PlJHNnk8i#NX}ATIiC$GoxEvIn}P$~s+MOc>xBBY{OjQ-RUopjR11XW?VwW&@j``eJxMIB^mjV>w|8xztc`7%S==Y*j4GDf?fQ? z#lnbV`n_@E!9Ip@Pt-zwq9R`rD%+SW?H|Mzxt`T}rS|~xQ}9sNQDi1I&jCZ0l9DC1 zye~0$|37`+|E`C+W$10E(JQhf>F;E>z{oPfLF(I9T#RCk|HQ-E7t3jDcr_%$gQTs2>{2P1MyYvkAw=OTg={KU@v z_$vJV&iJ3H&#|$qv48yI=n!7v8yueeR&8ST!Q=BYg<#3sFrC)?H}9226mUsFVULq( z9fdEkR(x@siZUmTpSTQ=C*ox3@fE|0bDgb2h>1vlZ0k3i+l2JKVUEePFHNQ}jgNZ~ zDCYDOEgszrk8F8Z))Y-@M^*$(hfG_#=DnMT01qQ7u?S zLsGDu`Kz8rQXCs=9eQi4GWkQmyZpZ!6*lGdZug^WNd97IDJ=M+O2n%5f5vh^B|0ZZ zz5Ct&CTqNNLZ{VC#8ONW0Q`uI-1o68e#DJC@@%%}UoQl}21Nr{AjE2T{aG`f`Evrn zUc}->qD+?Us1x4Do9AJxcCsB%A;E^^tCg3R&$z3ERaS7;$QZ=4A-yTG-p^tIIj#dx z)?f&N3&_=VjSk61tx5u~_tFlrQDNX+46(%n#vRBQp2B8SuQ#+2afn% zURdC!M(F$dFwL(5%Pk2gJLBOP67G$w{ytWz6a9%C>;cGjjbkg1ERxKIxW0isls1Co zR>=?`P=SI>e?*^4;iTegmky@zq|P9=WedJ;2vb00jU_L;&XQ`vObdc-yL?koO0C7z zfXiASfPi)WO(&ipR+gG*5FiKuLWiQzgx=<|8Vx7IT{Al{S)jhq*0|VNFwL2DElMbj zLpE-Zo{66vFglMF_Dht(Hg4RK$wJ_>sI%eR^gj9-Cu@){@`%2*q-huP7Rev&FECnd z*~2v&2E9pBPmC;%j<}M$FM_9{gPsvY!M9!>(M7#aZ#Gago$WwEPxzEqG1YY1`>1vb zF(2>o_K;+Fj-&6p*^E+SH&62%ig0(wa;p-v)752v^87)a%B(gtp-P#W;2+#v?xzkg z>Oxz3H~7g*!BKISyaS8)3OGw&uD~?YIsSpaK1%5r=b?9a!2KYp!mEJJ<;UWjQlZ_L zOXW*JtI=lW{Q(4bA2UV4^G%--uAzwl?xdeQLqkEmc`4vKz&NWJAviBCE(uS9#M8kU z85s=YYq^?KUXJ&_qNgGwTL#;wmwl8NXRmCMR@b*w;IKxp$)Ji3-7~9Y?pcfR%HSwjw4|Cbbp$*vtsbD+-dRKl$@#2_ zNG704;zC0)NDhYa#xlkjs4;WmdF&*l%!k>4l*EGHRE+aTKuXh)xgG^sLs(AH_te=s z@6>Wb5nf_tTB_7nhJr95nJoKM<>|vA1j+(Aq~$h!?gG3ru|sl2uzuw?AgW5mR5#qW zt@7Pw|Ia?1+c$^DrMlkILCj&ewY2GfU2fW(!E3{2o8F(x+Ixq%SukT(giF4S#-rD|Myn|~TMpaF8Xx4?n6kxPRUUc}>@8eu+hvgs z4U=-Gk^VD~t-b>WNJUGso0Z*scN=vHc-o})kO#b?+yZc|1G$>F@MB{TKYU4R0xjAj zbPM_u9=Qz@^8UG4X1-_3eZgMp9LMd%|GSr2^}x*5m=_qF*jCs7VFB@84NcA_HewzL zSWBbXQ|qBlCI_f64?TA6_&N8S6j{>HoHO~!yYjRQwWL$CIs+t|BZHL-J9ueH5(fqVh0;j?T`S@j1N0uqVH%&*eEYR& z3(5OlhD=}bdBFfwK=5mDf@e@iOL+jO1{tuJwCWlJThhTyssCX1?=47bMAyCLPVOVA+mTY8-VkP=wdu!rU9r znIfNfM-Sh}C6=DEtY6Z9{>emN)&8A> zmzSWgp;zl1MTzt^eZVzU@By#dw$%6sf|dcJk0I)Z6y2NTg=EGWo*QBPuGXx7(LfaG z@Rs&yAgc<;kN<=8{m(WCFxcUWPmU3jcadhE%FvBUBF?XVCCay zmRk7<01Bj*@!iKyo_~*P{I{3z!^BPU1<&7FDU{L;*guN~e2WeJ4A8=%~hvecu`f3G+ zYX=hghlt$nJN1PMrg{eT-?VMq>Pqefof(Le0_e$@embI}!`(X;l{tija4OIA9HI-j zAz6CgJNm1+2R0`QhH%2LzPRRbiMnE`Lj}$Cj2Si%w0848R=7>^G4M2 z)B^CcTpj0WnEqzk{1gKy)n%5g|8|wV?ApawLDfs%6b$lEy>6`No{3E!Qku~p)D2Ua zKzP&Z3t&+>CFX_ZMP}$nm1?2VBq-(DD8#G(WFq^bFjtj4G|;faztDHec`@p1P3 zqP1^R-;A5wVFFQ=1I2td&x6SQ^k*b;zM*uR-Uz${lIl+0@vVW6=71oyVC109WQ}X~ zsx~b@F^9q!Gj1Kb9kng;MC(vnYQSIVMvLRad<5)cCl|%kh}s(KE)d=Pp=>p;C_j6v z4Z7s?(C}XlFi2Z*z}l9gLHrLkF_&&28h*D5DFCrP`{R?Iu}8||%WY>>{K!|QIE3(u zA=D1TfzEwH6{6u}t%x=SrS6Ql?3s86;0!7pWN&4|`7 zJf}drkoGYBZ4tV78%o-lm}mEX)q-%_Qp!qY#x;yn%IfIi<)roW(-|osX)wRKkUc3F z#f}*=W2+A}|1A<6jW6_}Q)|(lS+7xXw(6H53lq}HaW9h`j~EgpLA__tYcWn$(~$AJ zT#KVX-NVCUxJbQ|JaQ=d%ov1=7_FIM)&vi`bIa~isx3ch0o{p-cM{{;=-da1tBzx+5oIv<4ycBf8g9*-7<1bz9-H?Hf2j-+1 z$t~e?r@DdrYVuB68&g}~uR&p591Y?>HEvcF$G?AH4*HCYIUZj?rY7<1ep{RSJe=)& z@%QsYzT9WHOc$bSDRTK+!qt^IOC(acf?-r)nJ@+n9)k>PsV0$3io}ws zB2@^M)!o^8Sw?zllGUuf-|#TzFxzAH48mpdR~NW9ty64WF5mJHf9mRi@wzjJLPa;E z6zBRbjB1Y!f8|yO&4~T$-x1gya-=3$62O?frupbed)2bavxz47!pJhDanbzJA zJafYJ9^SL-PB@bbaKk_+9oa}bSI-e!c=xbZ@EMK;R<^VlY%=A8L7=MfRbMUDP=Jse z4&@!M#hNB3#zgPG`KEEl%x40<%Z6Y6)bqfIYGE9}WDFBN2=AlG1bDjhH)E0eAjRx` z*EK5>Vs^)tle-eIfC^h%g|Go^g-7)W1&0ou91fe{@dl?_T%GduaQw@QyQ}}874McT z@}a#}!^oue2pJYgEz`D?&Zu^C#BzE%$kzDh@4A5iXH;Oso#;@5uq0n1z41(Su+{q) zp&41FAuEpp0P2{)T!lyMkV(pjcZ2evic}Buclcj(1u*0{k49zl9Az8;wLnDl7XeDQ zx#m&uASNa^t;+fiNOI2}7TvN9YIB{TUIqv?F#J3joT0o_2mg#(pe>L0Riu zX7B!040Yht2EbbUNWk-;w787yGTFfr6`JsYLS_&NnpN5@lA_HYr@cBQzq6P78H@6m zkC-N5nfv1u^^~l4bCS3%-9^AAvL3xS-iDM?c^?`tL)AO&_%g0}ev;!lRwy+xO_4tM z(REherWr18e`w@x+s*Nzq<#H0IyV!gKe77#aji?=P@xwt7(S;D5AeR;mj904dutb!+J&5W_#)n zY5GKiYW#9!;9sgAEpClJ2Hc$vYXFL*jQubEGGG6~lMLC{Cw4Y})y1vh`fE>{@xx26 znPwb)F_!y>wV;4?n{#Hz>&xRw4~~R897Udv^_s*pu+~C-_>U@v)5X$0ubw)cH;+6y z$$H6fZ=blyCf855=Xk;_KfSFlG1MgR-YkFFYiYTDK>IDlH12xDh#w4yvR6k-I}JsR z)Ep%3wWrnJ!~LtZ&t~wZt}igM;3^rS=E9Nh1LukV^RbHkV00q*W1*_afu1s*ldoHN zWfEvy$;sGX{ht1OoHd9-y2NGecT$7G*qcFcTX>Y?a87WU zXBM4Go+C1{DT)CNr0F}TM})KvXUR;242W#?fhbzwn;JSucR%^tXsgMlVz@VJ8wM_n zRF(t*-w$_31M4#svjw(;6a^8H? z@6Bl(xm+_X|CqU#E4FJ$3H4|sWOAC>Ju~eHlq^*N$Ba95>I=^t_`MS39{yy@^9dP=d^cW^aD6^AtG!MQxW#-%R2R!HQ;}AGAp!NSANWm44n6l6b+X) zgT`Gmxsyr(Sdc}IR>jp;~)mDX}!pKMx* zdCcR{D!r}hGey9{n3bMQ+WjH4Zv5;o-;ZcmDd)SASq;45dmCn6N6C?bXrw6tkKdDY zD~2Fk+E;A%Tn9?CB_A1OZ zrC8YFl86DQ>n9BXs7whNQf-G)h-_P2U)KhxDxzB$W}D1{Xs$}*6p`tmFn~+?#)pro zW?__7U*KuWp#vtn+yeJ^+xN5M8eFHW5!EMZOeA6vR=G3iKq22P+nalu3Va7AobH@R zD~2sHT-u+5W^E`m0EAx%jQ^;d&Aiiil|Hab6|zO%;fnW?B(y@C6TL-m3% zZub3R7AB`M+24AL2Z**{L^T`+S|N?C{W??Q12E@B=AV^C3WUG~Pmd+jy}uK3E_PA~`-8MuUG zsxwgG0waRdbY?BZ;4F2En~(u&V%fCgc%GE_0EdfSSPKR5mCVPSAK~wuts)XKMv-|# zja%Thi5@@RI0KmdPCgHaXDyYEC;Sq!=`n)Xz`cXnPg7~!Du69J&SEh-V|9oQf|yjR zd@oa3s>wZA_F6smr0#6ZYFd@`DAOI%a_1vBu<`iG@p8lZ6`c^l`OB{D#dF3KGdD#1 z`3fSaf8z<0m2{H?sG{CyrDTE0#Bqj+B#~92yAz1%{9V)Q5FMS;Q61vpLuj-)qfS0U18LJc2gQgV8dMe{Sulz-|kii72#6S z`KYe7!H(h`Y7Xi?v^OUR| zZNBdi7nl88HzRSi1Ru71slha2pzVq`!_Vwf|IT9N?mK?YnkuKR^p z>NiiRjF+-)R#oRqOHW%b@Qu#eS&>q&5P`YW8kic_fhfPh`P99PoKX6rPSp;;sykKl zd3#(2XXe|0P)p!)dn5r+WzyVarT+GOMmu_6u3N>zM@)r;j~#%y8q*gZF*|jFvmQg% z6>s*;A58ZcE)EpZFH@i98npq9vk1(96necw@lc9ctP!O{06$v-KIRu?&>%~N)MR9v zgJ`6esJ-`SJw9iyF%Q1Y@R7ppO8yahClY}pg+V6n+w>;aHeB{FUsRZjfb;#cfLw=3 z82tY8*uZZSAO#+y?OaWCnl>SBv@_{Y1v8a_S~MrDxyFMdsQw4#+pO|%T2KyYk zUxVHg|NA>kyzHWZPfl95PKE?2O`Z{@xE@l-sf&MSl`$zVdI?L6H(^=hF({^Q&hO+@R;bj>(bgXk3`(3wdBVOoql85f%w;r;)a$Ln0Fzocl0hNJ zH~kVXnj^&^95IdHe-V(bI<&rUfGesgtvy{G(HkfUrbY@X-eW&VAw&exeElvsl7PAF zQw|0%(h-;!(;no7zph0np2CE_OqqWP0RsPCvqYAL zL`qYlNR!E}Ri7a24a02_oyI@mzYH7IsLJ5X&#W9lmrXAp@0=~css56ys%3e=S=J`; zo>S4!QcGF}97?=>MkuI%ey-z&pP#_hv51t6nA4zB#MAI!+)?y} zXPA4-OOdjr70`YJ5?=0(jNLmZG5vjmh*#v8(JglzaKD}AA)ynrbhE4wH}sFW0S)g3 zk&hF=u%|b`f2=Q$Gp@NR4RGkxW&CE8Wnlv5%DP!wqB)DkV@ZQa=?m>T54)mMN(UqN zUQ4S@ud0YkhBOgYn&ZzG4RbIRw*Tv=jaiW4!D7k+Sh(9T9iIlgwuWUuOlZfK?J4mR zFhdAeyWtx~Dlxia7Tk2}1$HSZP)2ekOf40)L&x-yY7B9MY>%bDk*{mP>icl?P$#wr z`}mE7f7_Dz9d-*E-sz8uI_t0Pn60H!UUefSqH-0*V$P(D7f-4s+*8#tU%+1l6j~}W z*`fz<@pXUIs3Fs^&sv#DK8_zb(9)h0jJ>=4o@w`uNlgn9_5z#x7OR>uVe1@Xk^j$s z>DT}V)F_?TjuIz!iw_7?jh^B%oyh;cPR{$Et@nT95qrkon+C0-C`#;It43R^q_tud zEow_*wq`}!p!TNKR#S@B-VI{Ct*SjrDX~NO9-lwq`^b+u=j7x*_qoUGx}FzcIkz=X z=T9grTgy_kll^rjvQIWzcg#gNoIDHNz*RO*4lU{usBHVZ&w(k}2J}lShNB%T8I!

EBt#rgBa&X+~F5eWHhyIU$=YH9(9FEFAHHJL)_stl&N@Iz+e#0 zo$*}~dmDeCD4lF7fN#;p>lRK<(e`E&udhGUVPJ+=$?3nKeU>EsmE7@gE;{-FCo;Z0 zfW2;kdOS ze!68HN=C#yiu~%bRNEar)gs>l-Wj7e)f=tzN*s7ETM$G1k*7DE7FTh~^+w&M*35g;Qscx$K!kNU#4MyWZfKq^L)T%tlB zL@pP{Y#>;6(8c$gEuJnk{}V-)N++}?PnkPm=&M4OSGwqR?v3GLF<+R&;RJN8Ue43S}Z+WL-A&|PWh;^lJYMfS8_Mbs*c()$G z-N~~7nY=YNt6d3oG#A~1<_zkigu69f*JwGj1a9vf@nO@Nd)GPpBtx(+`ESgQD-%Ch zv6fO;?`G|dZNOTyLf%50yohte0RzHe-YtVEyBFV8%FJ?BSMgcJ_MlOmk{KP+)#_BM zI&|gL{lID%rwfnP%1idBA1)#JTIFon*zVQnS6#IHyy9d74G4!?c#4mQK89SdF&XLfQ47*;5n_Q z+f5d^xU6?AL)E8ufO9%YybDzPat}bvhb69Q35}`&1-A=0HJIP#xI4vynV-+W4Lr7g zHf*P=Z4=z)Ut4tc&R4Sq&>g!SuxtraWJ3n6-PUm;Zc+x%Dxu%p!l=eIUE^N^zuru4}fg2M7&~ z;pr3<{xh8-8+V3pDatyI1~B^)pe@8{U;XVdZ4D^M5RBZneBgopjWTv&vdPJxTDeb7L6VbvVf zCl`)LJZeqOQVpuQ|(}}jV33bUkqB(sb6JaceH#Hc~_$g99 zMdVFFSX&~op)A26sX5Ciu^x({pnzi~g2v=U%$%U&lUedEySz01>w{6gejH`=z}$S% z`k`%3Bb2V>5?23h^-=5BkwyymcLlhzY)mtB$>$SROb zPbH4;vnR4%66cl55f5OLbg`H51SQ20H`OVN^nhzwZZJA?S)jm|4+Q*M(%H-cC3*Sc zWQKK2bXgZ@Ndm3%|Gs>Ss?zQ63!52Als@EQ%~J-*zun#4hg%erIk9_ge*|Y3{O8L3 zFK;^4>HIg1H7Ff^iUi)`=p_4XzzrX^&A|0W=E25)@9ajS@>B8}{vN@7C5){!&zRuG zFZ(pvgXlgs@nq|^ME&~-7{{v1$H+tx+&;g~R&)Hk*qV3ZWWT-?Gu&7;@R|SSGbMl2 zE0(tIJ_uvx0FhA)Cm+}8g%{PbU?x=F-9LM#Z4DxGDOWJZsr~ub5h!s~RtBYv<+yh5 zE6W|Q%S%y<2GDeb-% zxn#vff>0E9)cJEwprMm$r1?UhK2qaA3SvEgy8_L8Wy#EFyY)1hr#T*akphzO2z6$o^(p! zSU~CFNSbH|onkaq!|j*kOo?s1sH?_wF}2@*>{W*3$E?IlVN}bkWwsRmhF)E1m&Pgo zX)Z@LEyi;shmr<_yLkqr=oqN=hxP{+PKDNRXe`ADr<*V0h2`2 zvwtK~SUphltw#(OT`$Y5T&l1v9us1{FgH9H>il9vMs4(h`JH2fm3n`rB6HaS$lYe# z^$vEhld8MM)$8$i)!j<=>b1|0>t}<#95DCq3m7%vxYqc^9#(nn7ih=q`+E{^8)(79 zrs>I_^s5J%U0GOIbF?R#Kq2H+2b&X3S4>`)Sd}z)SiXK6=iSbQr^$XI&^C?p#EiUY zyz#F;wBa|jSRl0Hn#x0K@+M;y`5=t{+2ixT7{9Y2)+a*Q;q8!RiD2EJuKJ*yzm0`KV+H^%}BW6^KYR; zdFlY>&JVV{dw0CXGicvwhd1;o>8w4D{-!yZ0dRCKo0kv)+c=o3HnH`2NMn01|KgkZ zZkrE5G%HpZtol~>6qq8sq8SBL6-7coUR2x({7({#zXvz_VxR2Z)l%pe(1-|WT1pQS z8{5|$>=Zhir&b-OOF`_J$bK(@k;#^1uPaP5ZCwK6D;yxChDjac81;0UU+3#P&Ln|z zaYzW-Z}AQlgy#=X)0z3O%V0jNemLopq}|u=zVX_Y13lG9=}+)ijch|xZYMdP6{)Ra zU2wZwczj=-@s47vwiEMl3C7&YpaI}5G9S{?y`YBlFAMN{dgO(csh#a~aKPX)o5`+O z$r13Y8=6m7O`ieJq^g_Tx+{j7A#q1^pUXMo6S+7~151rff82@rtrd1<-9`58=F`W@ zK9h2#9|Fh`1sxXQhQ>qV?Brox9}MfdM!JzZd=k$@s1~$ysif z=SOXHr|_*cAASETRZ+wdFEz1Yn1d~Xoh)N!0o|bjjh@#INAxIXuaZ&of7IuvCLaOH zE|uguA0PLfD>0^=pXFbi2&ItUn7%UWK{j3JW>pT@AAimQivMkl@a%jVsgd-aR9gAT zxGi3OEA*Psd3;&J?a&Dogml5K^TmPlio-aV6*O}D!?_5WpR%V(+fmp-{mF0O=E9Za-W5V3P-!#$JX88ngJ+=dO zBq#gw!2Z(j6^lrr;BCLCJ-%^K$&PjEB^SCIybt`(DIf1+hwYUq7@>?gy*W=V%ZI+3 zi7aA2^UwDs#zT5XGf-6f|5lY-e#@E1`o{bV17Eo%SV$Xe%{zRZ$1Jp_zyV^8|tKzwO)l7kTm`+T@lpr^i@GfH2T=iCOH-%B8d5;K9Hngp8!F7i#OXz z1ON-ZMxYksz(c;U8pf^AwLw)(a6-i2VY$)w*ZFLb%WESbZ4(E1zX`A*&x#GwtWNV` zUwcHx?rHw0ul8f($3YR#sgVAK3uI22KZ2%jt6d_MH$_aD3;eh_@=00}*WUO|@1^)f z=zgiN`|K`d%X?=;aJt)Y=5=iMv}I0ce%&2sM8ZeFSP=kOSXDC}QA%6|ZS`_}PB}lB zyZGl!$vTacBHxnBUobpQ^3Xi}qi`AiQ~Lf3hp%IibtV(y2`ndx-CSP5R*VKU8&1%s zmf97jKx-L-c$t}6$k6Ggi|VnNmapcPDT~2^msYn~izp)7r7-bZU3GrU+WhVw#lv!+ zU#KZs3#KK-5`oF%2uVz8v19AfHRqETO~7{Y)dGTC_+-m3+TkC)wumUCzr<3fIJu&EIyE#Ft=mAu=DU&$IHa{^-kN5?(xh6AJW<9p zV0=obipLi~h;Pi$iUebR}_Bv*iavZ_@-?h zFYxen3Gk1RPbe8n8wvz3ycCqV;gk>bA;f?Zq0fvmq!2R2@ zc6a-yllqo_W&&^f6x;Jq{?7k4?vJk~WLa81ls8cSIL8JP7S*)^04m&``n-no6=^;OvRY2Z!C=($xpxC7g)pjP zVx_tfQS&J34TNbEv;Eo4O!|~vZ}?S^YZVJEo3%`GLO${dOS|0jZ-YSW$RUjZvCAUn z^T9^-hkF;a;Ah=D9u-o$=Ty9S`%ATgpp+oRMy69tD#OB#10*pKhWFBJqUp~Cs8UU@ zAY#QZ8l8$@tdV2+PaqI&ZZ>-E-{bKO|Ihw}RE>^dT0bJnFHLnr@(2LFt4Fas*J`>X zLNa4rcr=)x#}(H=^cwlwf4_mK85nnaQU$83-WR&M>6fButCaM(HKQV$HYmNGWoi-O zIy)j)Q=3*Z+_(Hy$t+ZmdOb^7-Pio^S_uV=$o*rfb(_uDntpxZ^)u%)B3F&`MHC%F zviNd}l9nBaHJb*^@N^G$Vzs?Dr1|&p*99uyYv7kYMUJsTPuHKdoaT!V92+^bpgMkTx(YR8p-_UPlHhDIr$xlDVE1Xokz ziX&$rv(4&Bt|4(#A1*sW6y{-vr{(u1X$sCurvC81CV8y!WG z*SMy&JR;~#?SPn-#=$_sVK7O;PQ@1-yL%l(5GR5PJjI|~!o9torc5bvZV1@|s+0~n zO+eHeEw`A+;wZzgxD(+NR3)DDLvB~KO{VD{NF|)>xfC%W#eG+^xIO}qOGlN?JEHX#BWn_jVMF2K z{IRcP=NP~sjemL1+5ga!l3S#xr{6!QzcO>)p%?ZMQruL-ik zY;JE}C#nh%T%|2ee-))JP@P_PO4$&a9vsW8BbaTZmx(+vUj65qM{DWYEi}OAuf-iJ zr7?Bj!(3BLT>N2i^!GT74{qCpK6xsOP$Gl=7AI%I)8P1UZwIIOorePZ%{FHDv+ML( z1jc9Azjeh3oUvG>r4s3y{~O-hoj?ys?5SlPVM3u9A!0)N!@H=_J{xUk_Dlu;n(4XQwfRFg!#a^_`SIP;)r&6S*9OoTt_(_=Ib z2ewaja#3&nV=C(qk8WTWvhC>obs9Ptk`!wV5>Qmf-TF}G$5|3oC2Mbd+ zm@jPEyCRyfgWvD;%t~bpdh`^Ror+EcUhzfbW%04%)*5ex7e4iPzE(gVsa2GBHgNT> zI}(d(_oUU#2JJcSgx2gad=|l+<#^b(wSm6)+~CgWpamQW>!doBJjn)3@Op7`wXLx1l?$+9-4pvExUAz&X6*n zk8z%(HTKmY;(6wm<6>JIub`kWV9G6z@tZ#sE|;5XHRLM)Ic*-v1sShR;k(zNc5JFI z4aAJ_TMoq!C1aES(F_6%_!Ut-vsK-wcdg=b&$*dt%yf)~scgM0{JGq0L)$i})K8bahX_+?!y={PfTHW)4mZ5}A<)1b+Tpj- zx5ahXpCTg)M8sf`-ALC+mm#)J{rN0Un!X)6t$nlS5rEwAlp|9zMlU>_9K89?3B(HX zE{MYuoU}GGOk^xmGFsj{7Qc7L#zYf~0thmR@dV~W(-LU$buYely>tc&gCGUa`U_6x z)L}4sM$NI9zcq1%z?{XTHQ6v2N&e|?#G2aHMB~+KA^C$Y?4lMMOrw@eLBeuB`WFQH z!~T5g33SCZ?l7?=62MzY9_`Tn*aeUg67%ipfRTZrmXLdSL{bmR0Ecm*P2^{EP|h=4 zUpHLuOHeBQ!fHgBJJ7iWEVILCZWZoOY4`Px)*ee(JU*t!=v-uG!JIC zgs5PnZDft}LHYNMN#uGEfjTCy0B!aKu%aKkd5uP69!20;ihC$e^FxDbM0N{rd<#h{ zrXipc<+x;L;uteu3B7)w8`IevJHOZ@e4F(S(%1+Ad%J+TJ@CTnSBxbdXZ(c;M{hqO zqakN)7)UQ4VtDi=!xISgY&#Ie4fQYcEl|5|*<*_kTrBl?eoH1{wAWCT)jDUsM0AgH zu@JNQuQm(Rj&}H_CdqdvIOa>;SZcMLSyomEp6_FNiHae&yk=AVw@S4?u{9vEa-|j=`f4-zc|Uis62o^>sPer zO*xstr44$gH>ibDGG&u}x(77gW0NenBqO3UC3wE(w{lv<~2RGu@9s7?kG zfw>mbveF@$#>T!!aZ_+yh@h1||H?Ikmiz1g=s-UQ^3)yf-!7&s%Hm}VO?4eoAYA}U z?m)kme|0q)2IQaCFk1@KWG$mqNIyVvQ&o$xW2Ip9rrv7*sVg(d36_xYF68#%sX*`J z!e*ML&QtMIp9BZzTuKbAI4O&vi32TD*rG`IQ3Z_M9aaIzlU zSV(yXvTjlIecAYyO670E^Rn+Wg7kmUkw5l+#+-M4GX)Z-PMPH9L(lXD)GajLz529v zLpfthAp|^1(L(E{r8erM>a9FcDY1q79x&`mCg0k@`Z?agm*}GWc}IX}zQ8vSgl8yj z`&r;`OSPG7Ktp4S+UQAUtP(mIl>+@|5lyn5m1S4^EVlnw+Sx@*kqV1^0#A2k^<9bV zPbh?^+E8TGnj+v8z&Z(Ht7Fk$%&?Bslsa~lKVa0*ZQf_Y^Rn|tjYdUK9M^E0ZEkEj ze#rZ-=oD9aZ0a(yD)&5s#cJJDZN2!IWG%4{YP~~!%C`j;Ns7)RzK0aB2>ptQ2jHy# zM)S%eS3mxdoSRoW%pu)@AcmCPuKbvT@_i%!AZJTCSDG?*eX7wm*XrM3Qzh#=l~^Q? zh+M4jt{NLHx}70VN$mzDn_FvoGN>{+e%Wlc1H`n_K_QN%IZ&9bvx5AvR(Ku#)nEoM zWy~`+Zr~Lz^GEqazOkn#&-UDGAV=($iK7pRouunL&Fef=(_aqL=mwI;haxE$b|51e zbwnq_z74YVoZm0;doaF0^We;9h7%QHCmm}KGrr^mlfm{qKBnMezCC>%GOry7_}zf#-4j47`mYyUOQZty1|&zU>>S%u&Nq8Ulyl7Th?1c3%|18GLd&99XjjFwP{$dR zqiz^O-(V%%)sp2$7kF(RIVqvlgfy}R{nnW zkkkbGdT=Wl>Y6a>TMZI}dDmne{Ar5dR^mTnlw6oS_0UKa`bgWlDnl z6)Du`EUVrEUjfn2I7vc02V*JG#nWN@3}%NT^-gqK3wyEONoK|$<7~>HT=j*C&c8Xn zJSHCOvL|v<+PBfQC8x>Vb>B&d0Hl;^OoT6tQdFNz4*V`%k$gTR7NMcdf^LI_XmS28 z8+%bon0eU#7w5^TQKipYQk5finp5!YPxq`{JJSDRsb6G+i#!!kEO1I};pit~&p5Gg z!AEL4w?uyc+#HYxE|e06KCcFewbK1^zgKEn_aNHNCjEz9mn1F4?mXF*h|4r<5WW4a zbp{}yyOjYZa0M+|^|&{by@hM%YsEmSXXcM%btPH9eZ76)$aNX^R+bl=MMb_2v3x6_ zPk%>38l2h#r6H0k{<`-Rod)xXa_;o?Az8jH-=K+b9#Tvxp_ZV}+DhHAVv7rkJ zu_70e0$MaOI|*;kZW^DTJ&#DG^!@5HG*#cce6b7sh$J0d;yZ7(vMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY From 9255785c311a5287d588445eb4c7fe98ec0a9652 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 3 Oct 2012 00:13:26 -0500 Subject: [PATCH 489/508] Android HID: Check the interface is valid before trying to open it. --- .../src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java index ae406121d..59380fbf0 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/HidUAVTalk.java @@ -257,6 +257,12 @@ public class HidUAVTalk extends TelemetryTask { UsbEndpoint ep1 = null; UsbEndpoint ep2 = null; + if (connectDevice.getInterfaceCount() < 2) { + if (ERROR) Log.e(TAG, "Interface count for USB device incorrect"); + telemService.toastMessage("Failed to connect"); + return false; + } + // Using the same interface for reading and writing usbInterface = connectDevice.getInterface(0x2); if (usbInterface.getEndpointCount() == 2) From a39cbdbcb1e071ac449f4f0956497f4e37289f08 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 3 Oct 2012 10:43:03 -0500 Subject: [PATCH 490/508] RadioBridge: Send data from UAVTalk non blocking, otherwise it can lock up the packet handler. --- flight/Modules/RadioComBridge/RadioComBridge.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 188f5f974..6776f111d 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -717,7 +717,7 @@ static int32_t UAVTalkSend(UAVTalkComTaskParams *params, uint8_t *buf, int32_t l } #endif /* PIOS_INCLUDE_USB */ if(outputPort) - return PIOS_COM_SendBuffer(outputPort, buf, length); + return PIOS_COM_SendBufferNonBlocking(outputPort, buf, length); else return -1; } From 2d4e0b397a242a11a23633cb27f535b5fa359efe Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 2 Oct 2012 20:59:43 -0700 Subject: [PATCH 491/508] RFM22B: Removed setting register 0x58 in the rfm22_setDatarate call, which was breaking all data rates < 100000 bps. Also temporatily fixed the datarate at 64kbps. --- flight/PiOS/Common/pios_rfm22b.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 2235f64e5..3c9398694 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -1137,6 +1137,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) int lookup_index = 0; while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) lookup_index++; + lookup_index = 10; datarate_bps = data_rate[lookup_index]; @@ -1166,12 +1167,14 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) // rfm22_afc_limiter rfm22_write(0x2A, reg_2A[lookup_index]); +/* This breaks all bit rates < 100000! if (datarate_bps < 100000) // rfm22_chargepump_current_trimming_override rfm22_write(0x58, 0x80); else // rfm22_chargepump_current_trimming_override rfm22_write(0x58, 0xC0); +*/ // rfm22_tx_data_rate1 rfm22_write(0x6E, reg_6E[lookup_index]); @@ -1550,7 +1553,7 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) } // Packet has been sent - if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) + else if (rfm22b_dev->int_status1 & RFM22_is1_ipksent) { // Free the tx packet PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet); From 36437f695ffe6c5859d8d4efbe12cf8b2d860778 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 2 Oct 2012 19:52:21 -0700 Subject: [PATCH 492/508] RFM22B: Moved radio status reporting from the radio module into the rfm22b driver task. --- flight/Modules/Radio/radio.c | 23 ------ flight/PiOS/Common/pios_rfm22b.c | 135 +++++++++++++++++-------------- 2 files changed, 76 insertions(+), 82 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 01fd7bb2b..b5beb1359 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -408,8 +408,6 @@ static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc) */ static void radioStatusTask(void *parameters) { - PHStatusPacket status_packet; - while (1) { PipXStatusData pipxStatus; uint32_t pairID; @@ -468,27 +466,6 @@ static void radioStatusTask(void *parameters) // Update the object PipXStatusSet(&pipxStatus); - // Broadcast the status. - { - static uint16_t cntr = 0; - if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS) - { - // Queue the status message - status_packet.header.destination_id = 0xffffffff; - status_packet.header.type = PACKET_TYPE_STATUS; - status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet); - status_packet.header.source_id = pipxStatus.DeviceID; - status_packet.retries = data->comTxRetries; - status_packet.errors = data->packetErrors; - status_packet.uavtalk_errors = data->UAVTalkErrors; - status_packet.dropped = data->droppedPackets; - status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id); - PHPacketHandle sph = (PHPacketHandle)&status_packet; - PHTransmitPacket(PIOS_PACKET_HANDLER, sph); - cntr = 0; - } - } - vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS); } } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 3c9398694..96d735d61 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -54,6 +54,7 @@ #include #include #include +#include /* Local Defines */ #define STACK_SIZE_BYTES 200 @@ -62,11 +63,12 @@ #define EVENT_QUEUE_SIZE 5 #define PACKET_QUEUE_SIZE 3 -// RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms). -// A 256 byte message at 56kbps should take less than 40ms -// Note: This timeout should be rate dependent. +// The maximum amount of time without activity before initiating a reset. #define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms +// The time between updates over the radio link. +#define RADIOSTATS_UPDATE_PERIOD_MS 250 + // this is too adjust the RF module so that it is on frequency #define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default #define OSC_LOAD_CAP_1 0x7D // board 1 @@ -94,28 +96,6 @@ #define SYNC_BYTE_3 0x4B // #define SYNC_BYTE_4 0x59 // -// ************************************ -// the default RF datarate - -//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec -#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec -//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING - -// ************************************ - -#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps - #ifndef RX_LED_ON #define RX_LED_ON #define RX_LED_OFF @@ -258,9 +238,12 @@ struct pios_rfm22b_dev { int32_t afc_correction_Hz; int8_t rx_packet_start_afc_Hz; + // The status packet + PHStatusPacket status_packet; + // The maximum time (ms) that it should take to transmit / receive a packet. uint32_t max_packet_time; - portTickType packet_start_time; + portTickType packet_start_ticks; }; struct pios_rfm22b_transition { @@ -308,6 +291,7 @@ static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_ static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev); static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev); +static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev); // SPI read/write functions static void rfm22_assertCs(); @@ -587,7 +571,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet. rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(rfm22b_dev->cfg.maxRFBandwidth) + 0.5); - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary( rfm22b_dev->isrPending ); @@ -791,7 +775,8 @@ static void PIOS_RFM22B_Task(void *parameters) struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)parameters; if (!PIOS_RFM22B_validate(rfm22b_dev)) return; - static portTickType lastEventTime; + portTickType lastEventTicks = xTaskGetTickCount(); + portTickType lastStatusTicks = lastEventTicks; while(1) { @@ -803,7 +788,7 @@ static void PIOS_RFM22B_Task(void *parameters) // Wait for a signal indicating an external interrupt or a pending send/receive request. if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { rfm22b_dev->irqs_processed++; - lastEventTime = xTaskGetTickCount(); + lastEventTicks = xTaskGetTickCount(); // Process events through the state machine. enum pios_rfm22b_event event; @@ -821,8 +806,11 @@ static void PIOS_RFM22B_Task(void *parameters) else { // Has it been too long since the last event? - portTickType timeSinceEvent = xTaskGetTickCount() - lastEventTime; - if ((timeSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) + portTickType curTicks = xTaskGetTickCount(); + if (curTicks < lastEventTicks) + lastEventTicks = curTicks; + portTickType ticksSinceEvent = curTicks - lastEventTicks; + if ((ticksSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT) { // Transsition through an error event. enum pios_rfm22b_event event = RFM22B_EVENT_ERROR; @@ -832,34 +820,36 @@ static void PIOS_RFM22B_Task(void *parameters) // Clear the event queue. while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE) ; - lastEventTime = xTaskGetTickCount(); - } - else - { - rfm22b_dev->resets = rfm22b_dev->state; - enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; - while(event != RFM22B_EVENT_NUM_EVENTS) - event = rfm22_process_state_transition(rfm22b_dev, event); + lastEventTicks = xTaskGetTickCount(); } } // Have we locked up sending / receiving a packet? - if (rfm22b_dev->packet_start_time > 0) + if (rfm22b_dev->packet_start_ticks > 0) { - portTickType cur_time = xTaskGetTickCount(); + portTickType cur_ticks = xTaskGetTickCount(); // Did the clock wrap around? - if (cur_time < rfm22b_dev->packet_start_time) - rfm22b_dev->packet_start_time = (cur_time > 0) ? cur_time : 1; + if (cur_ticks < rfm22b_dev->packet_start_ticks) + rfm22b_dev->packet_start_ticks = (cur_ticks > 0) ? cur_ticks : 1; // Have we been sending this packet too long? - if ((cur_time - rfm22b_dev->packet_start_time) > (rfm22b_dev->max_packet_time * 5)) + if (((cur_ticks - rfm22b_dev->packet_start_ticks) / portTICK_RATE_MS) > (rfm22b_dev->max_packet_time * 3)) { enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT; while(event != RFM22B_EVENT_NUM_EVENTS) event = rfm22_process_state_transition(rfm22b_dev, event); } } + + // Queue up a status packet if it's time. + portTickType curTicks = xTaskGetTickCount(); + // Rollover + if (curTicks < lastStatusTicks) + lastStatusTicks = curTicks; + if (((curTicks - lastStatusTicks) / portTICK_RATE_MS) > RADIOSTATS_UPDATE_PERIOD_MS) + if (rfm22_sendStatus(rfm22b_dev)) + lastStatusTicks = curTicks; } } @@ -1206,7 +1196,7 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev) { - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1254,9 +1244,9 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_RX_MODE; } rfm22b_dev->tx_packet = p; - rfm22b_dev->packet_start_time = xTaskGetTickCount(); - if (rfm22b_dev->packet_start_time == 0) - rfm22b_dev->packet_start_time = 1; + rfm22b_dev->packet_start_ticks = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_ticks == 0) + rfm22b_dev->packet_start_ticks = 1; // disable interrupts rfm22_write(RFM22_interrupt_enable1, 0x00); @@ -1319,6 +1309,36 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) return RFM22B_EVENT_TX_STARTED; } +static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev) +{ + PHPacketHandle sph = (PHPacketHandle)&(rfm22b_dev->status_packet); + + // Queue the status message + rfm22b_dev->status_packet.header.source_id = rfm22b_dev->deviceID; + rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast + rfm22b_dev->status_packet.header.type = PACKET_TYPE_STATUS; + rfm22b_dev->status_packet.header.data_size = PH_STATUS_DATA_SIZE(&(rfm22b_dev->status_packet)); + rfm22b_dev->status_packet.header.tx_seq = 0; + rfm22b_dev->status_packet.header.rx_seq = 0; + rfm22b_dev->status_packet.errors = rfm22b_dev->errors; + rfm22b_dev->status_packet.resets = rfm22b_dev->resets; + rfm22b_dev->status_packet.retries = 0; + rfm22b_dev->status_packet.uavtalk_errors = 0; + rfm22b_dev->status_packet.dropped = 0; + + // Add the error correcting code. + encode_data((unsigned char*)sph, PHPacketSize(sph), (unsigned char*)sph); + if (xQueueSend(rfm22b_dev->packetQueue, &sph, 0) != pdTRUE) + return false; + + // Process a SEND_PACKT event. + enum pios_rfm22b_event event = RFM22B_EVENT_SEND_PACKET; + while(event != RFM22B_EVENT_NUM_EVENTS) + event = rfm22_process_state_transition(rfm22b_dev, event); + + return true; +} + // ************************************ /** @@ -1364,9 +1384,9 @@ static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22 // Valid preamble detected if (rfm22b_dev->int_status2 & RFM22_is2_ipreaval) { - rfm22b_dev->packet_start_time = xTaskGetTickCount(); - if (rfm22b_dev->packet_start_time == 0) - rfm22b_dev->packet_start_time = 1; + rfm22b_dev->packet_start_ticks = xTaskGetTickCount(); + if (rfm22b_dev->packet_start_ticks == 0) + rfm22b_dev->packet_start_ticks = 1; RX_LED_ON; return RFM22B_EVENT_PREAMBLE_DETECTED; } @@ -1505,7 +1525,7 @@ static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev) } // Start a new transaction - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_RX_COMPLETE; } @@ -1560,7 +1580,7 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->tx_packet = 0; rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0; // Start a new transaction - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_TX_COMPLETE; } @@ -1650,7 +1670,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->afc_correction_Hz = 0; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; // **************** // read the RF chip ID bytes @@ -1734,9 +1754,6 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) if (freq_hop_step_size > 255) freq_hop_step_size = 255; rfm22b_dev->frequency_hop_step_size_reg = freq_hop_step_size; - // set the RF datarate - rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, true); - // FIFO mode, GFSK modulation uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd; rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk); @@ -1841,14 +1858,14 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev) { rfm22b_dev->resets++; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_TX_START; } static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev) { rfm22b_dev->resets++; - rfm22b_dev->packet_start_time = 0; + rfm22b_dev->packet_start_ticks = 0; return RFM22B_EVENT_INITIALIZE; } From 5eed0db61bc352a2f4d4053953a7c7bfbdae43b1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 3 Oct 2012 15:10:12 -0500 Subject: [PATCH 493/508] Hardcode rates to 64kbps --- flight/board_hw_defs/pipxtreme/board_hw_defs.c | 2 +- flight/board_hw_defs/revomini/board_hw_defs.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/board_hw_defs/pipxtreme/board_hw_defs.c index e436f3975..c43658bde 100644 --- a/flight/board_hw_defs/pipxtreme/board_hw_defs.c +++ b/flight/board_hw_defs/pipxtreme/board_hw_defs.c @@ -226,7 +226,7 @@ struct pios_rfm22b_cfg pios_rfm22b_pipx_cfg = { .minFrequencyHz = 434000000 - 2000000, .maxFrequencyHz = 434000000 + 2000000, .RFXtalCap = 0x7f, - .maxRFBandwidth = 128000, + .maxRFBandwidth = 64000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW .slave_num = 0, .gpio_direction = GPIO0_TX_GPIO1_RX, diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/board_hw_defs/revomini/board_hw_defs.c index 8785d192f..8d5e92517 100644 --- a/flight/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/board_hw_defs/revomini/board_hw_defs.c @@ -399,7 +399,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_rm1_cfg = { .minFrequencyHz = 434000000 - 2000000, .maxFrequencyHz = 434000000 + 2000000, .RFXtalCap = 0x7f, - .maxRFBandwidth = 128000, + .maxRFBandwidth = 64000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW .slave_num = 0, .gpio_direction = GPIO0_RX_GPIO1_TX, @@ -412,7 +412,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = { .minFrequencyHz = 434000000 - 2000000, .maxFrequencyHz = 434000000 + 2000000, .RFXtalCap = 0x7f, - .maxRFBandwidth = 128000, + .maxRFBandwidth = 64000, .maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW .slave_num = 0, .gpio_direction = GPIO0_TX_GPIO1_RX, From 9b9d0c0d1e094bd01b7dbf8a3a4791fd50913c2d Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Wed, 3 Oct 2012 20:03:35 -0700 Subject: [PATCH 494/508] RFM22B: Added back configuration of the RF Power and RF Datarate. Also added setting of the destination ID in the rfm22b driver. --- flight/Modules/Radio/radio.c | 115 ++++++++++++++--------------- flight/PiOS/Common/pios_rfm22b.c | 83 +++++++++++---------- flight/PiOS/inc/pios_rfm22b.h | 32 +++++++- flight/PiOS/inc/pios_rfm22b_priv.h | 34 ++++----- 4 files changed, 143 insertions(+), 121 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index b5beb1359..8820e4081 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -185,69 +185,66 @@ static int32_t RadioInitialize(void) const struct pios_board_info * bdinfo = &pios_board_info_blob; pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - // Not appropriate for a constant struct. Is it necessary to make a local copy of the cfg? - // We should probably be consistent with other drivers and allocate a device structure with - // dynamical configuration in it -#if 0 - pios_rfm22b_cfg->frequencyHz = pipxSettings.Frequency; - pios_rfm22b_cfg->RFXtalCap = pipxSettings.FrequencyCalibration; - switch (pipxSettings.RFSpeed) - { - case PIPXSETTINGS_RFSPEED_2400: - pios_rfm22b_cfg->maxRFBandwidth = 2000; - break; - case PIPXSETTINGS_RFSPEED_4800: - pios_rfm22b_cfg->maxRFBandwidth = 4000; - break; - case PIPXSETTINGS_RFSPEED_9600: - pios_rfm22b_cfg->maxRFBandwidth = 9600; - break; - case PIPXSETTINGS_RFSPEED_19200: - pios_rfm22b_cfg->maxRFBandwidth = 19200; - break; - case PIPXSETTINGS_RFSPEED_38400: - pios_rfm22b_cfg->maxRFBandwidth = 32000; - break; - case PIPXSETTINGS_RFSPEED_57600: - pios_rfm22b_cfg->maxRFBandwidth = 64000; - break; - case PIPXSETTINGS_RFSPEED_115200: - pios_rfm22b_cfg->maxRFBandwidth = 128000; - break; - } - switch (pipxSettings.MaxRFPower) - { - case PIPXSETTINGS_MAXRFPOWER_125: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_0; - break; - case PIPXSETTINGS_MAXRFPOWER_16: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_1; - break; - case PIPXSETTINGS_MAXRFPOWER_316: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_2; - break; - case PIPXSETTINGS_MAXRFPOWER_63: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_3; - break; - case PIPXSETTINGS_MAXRFPOWER_126: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_4; - break; - case PIPXSETTINGS_MAXRFPOWER_25: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_5; - break; - case PIPXSETTINGS_MAXRFPOWER_50: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_6; - break; - case PIPXSETTINGS_MAXRFPOWER_100: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_7; - break; - } -#endif - /* Initalize the RFM22B radio COM device. */ if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) return -1; + // Set the maximum radio RF power. + switch (pipxSettings.MaxRFPower) + { + case PIPXSETTINGS_MAXRFPOWER_125: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); + break; + case PIPXSETTINGS_MAXRFPOWER_16: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); + break; + case PIPXSETTINGS_MAXRFPOWER_316: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); + break; + case PIPXSETTINGS_MAXRFPOWER_63: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); + break; + case PIPXSETTINGS_MAXRFPOWER_126: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); + break; + case PIPXSETTINGS_MAXRFPOWER_25: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); + break; + case PIPXSETTINGS_MAXRFPOWER_50: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); + break; + case PIPXSETTINGS_MAXRFPOWER_100: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); + break; + } + + switch (pipxSettings.RFSpeed) { + case PIPXSETTINGS_RFSPEED_2400: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_2000, true); + break; + case PIPXSETTINGS_RFSPEED_4800: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_4000, true); + break; + case PIPXSETTINGS_RFSPEED_9600: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_9600, true); + break; + case PIPXSETTINGS_RFSPEED_19200: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_19200, true); + break; + case PIPXSETTINGS_RFSPEED_38400: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_32000, true); + break; + case PIPXSETTINGS_RFSPEED_57600: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_64000, true); + break; + case PIPXSETTINGS_RFSPEED_115200: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_128000, true); + break; + } + + // Set the radio destination ID. + PIOS_RFM22B_SetDestinationId(pios_rfm22b_id, pipxSettings.PairID); + // Initialize the packet handler PacketHandlerConfig pios_ph_cfg = { .default_destination_id = 0xffffffff, // Broadcast diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 96d735d61..bd3925f03 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -62,6 +62,7 @@ #define ISR_TIMEOUT 5 // ms #define EVENT_QUEUE_SIZE 5 #define PACKET_QUEUE_SIZE 3 +#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_64000 // The maximum amount of time without activity before initiating a reset. #define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms @@ -164,8 +165,12 @@ struct pios_rfm22b_dev { uint32_t spi_id; uint32_t slave_num; + // The device ID uint32_t deviceID; + // The destination ID + uint32_t destination_id; + // The task handle xTaskHandle taskHandle; @@ -184,6 +189,9 @@ struct pios_rfm22b_dev { // the transmit power to use for data transmissions uint8_t tx_power; + // The RF datarate lookup index. + uint8_t datarate; + // The state machine state and the current event enum pios_rfm22b_state state; // The event queue handle @@ -558,6 +566,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; + rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE; // Initialize the packets. rfm22b_dev->rx_packet = NULL; @@ -570,7 +579,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu g_rfm22b_dev = rfm22b_dev; // Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet. - rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(rfm22b_dev->cfg.maxRFBandwidth) + 0.5); rfm22b_dev->packet_start_ticks = 0; // Create a semaphore to know if an ISR needs responding to @@ -672,24 +680,20 @@ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) return 0; } -void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr) +void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; if(!PIOS_RFM22B_validate(rfm22b_dev)) return; + rfm22b_dev->tx_power = tx_pwr; +} - switch (tx_pwr) - { - case 0: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW - case 1: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW - case 2: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW - case 3: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW - case 4: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW - case 5: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW - case 6: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW - case 7: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW - default: break; - } +void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return; + rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id; } int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) @@ -1120,42 +1124,41 @@ uint32_t rfm22_freqHopSize(void) // // This gives 2(45 + 9.6) = 109.2kHz. -void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) +void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening) { + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return; - // Find the closest data rate that is >= the value passed in - int lookup_index = 0; - while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) - lookup_index++; - lookup_index = 10; - - datarate_bps = data_rate[lookup_index]; + uint32_t datarate_bps = data_rate[datarate]; + rfm22b_dev->datarate = datarate; + rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5); // rfm22_if_filter_bandwidth - rfm22_write(0x1C, reg_1C[lookup_index]); + rfm22_write(0x1C, reg_1C[datarate]); // rfm22_afc_loop_gearshift_override - rfm22_write(0x1D, reg_1D[lookup_index]); + rfm22_write(0x1D, reg_1D[datarate]); // RFM22_afc_timing_control - rfm22_write(0x1E, reg_1E[lookup_index]); + rfm22_write(0x1E, reg_1E[datarate]); // RFM22_clk_recovery_gearshift_override - rfm22_write(0x1F, reg_1F[lookup_index]); + rfm22_write(0x1F, reg_1F[datarate]); // rfm22_clk_recovery_oversampling_ratio - rfm22_write(0x20, reg_20[lookup_index]); + rfm22_write(0x20, reg_20[datarate]); // rfm22_clk_recovery_offset2 - rfm22_write(0x21, reg_21[lookup_index]); + rfm22_write(0x21, reg_21[datarate]); // rfm22_clk_recovery_offset1 - rfm22_write(0x22, reg_22[lookup_index]); + rfm22_write(0x22, reg_22[datarate]); // rfm22_clk_recovery_offset0 - rfm22_write(0x23, reg_23[lookup_index]); + rfm22_write(0x23, reg_23[datarate]); // rfm22_clk_recovery_timing_loop_gain1 - rfm22_write(0x24, reg_24[lookup_index]); + rfm22_write(0x24, reg_24[datarate]); // rfm22_clk_recovery_timing_loop_gain0 - rfm22_write(0x25, reg_25[lookup_index]); + rfm22_write(0x25, reg_25[datarate]); // rfm22_afc_limiter - rfm22_write(0x2A, reg_2A[lookup_index]); + rfm22_write(0x2A, reg_2A[datarate]); /* This breaks all bit rates < 100000! if (datarate_bps < 100000) @@ -1167,9 +1170,9 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) */ // rfm22_tx_data_rate1 - rfm22_write(0x6E, reg_6E[lookup_index]); + rfm22_write(0x6E, reg_6E[datarate]); // rfm22_tx_data_rate0 - rfm22_write(0x6F, reg_6F[lookup_index]); + rfm22_write(0x6F, reg_6F[datarate]); // Enable data whitening // uint8_t txdtrtscale_bit = rfm22_read(RFM22_modulation_mode_control1) & RFM22_mmc1_txdtrtscale; @@ -1177,16 +1180,16 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) if (!data_whitening) // rfm22_modulation_mode_control1 - rfm22_write(0x70, reg_70[lookup_index] & ~RFM22_mmc1_enwhite); + rfm22_write(0x70, reg_70[datarate] & ~RFM22_mmc1_enwhite); else // rfm22_modulation_mode_control1 - rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite); + rfm22_write(0x70, reg_70[datarate] | RFM22_mmc1_enwhite); // rfm22_modulation_mode_control2 - rfm22_write(0x71, reg_71[lookup_index]); + rfm22_write(0x71, reg_71[datarate]); // rfm22_frequency_deviation - rfm22_write(0x72, reg_72[lookup_index]); + rfm22_write(0x72, reg_72[datarate]); rfm22_write(RFM22_ook_counter_value1, 0x00); rfm22_write(RFM22_ook_counter_value2, 0x00); @@ -1850,7 +1853,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22_setFreqCalibration(rfm22b_dev->cfg.RFXtalCap); rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->cfg.frequencyHz); - rfm22_setDatarate(rfm22b_dev->cfg.maxRFBandwidth, true); + RFM22_SetDatarate((uint32_t)rfm22b_dev, rfm22b_dev->datarate, true); return RFM22B_EVENT_INITIALIZED; } diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 451480960..65c823283 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -49,9 +49,39 @@ struct pios_rfm22b_cfg { enum gpio_direction gpio_direction; }; +enum rfm22b_tx_power { + RFM22_tx_pwr_txpow_0 = 0x00, // +1dBm .. 1.25mW + RFM22_tx_pwr_txpow_1 = 0x01, // +2dBm .. 1.6mW + RFM22_tx_pwr_txpow_2 = 0x02, // +5dBm .. 3.16mW + RFM22_tx_pwr_txpow_3 = 0x03, // +8dBm .. 6.3mW + RFM22_tx_pwr_txpow_4 = 0x04, // +11dBm .. 12.6mW + RFM22_tx_pwr_txpow_5 = 0x05, // +14dBm .. 25mW + RFM22_tx_pwr_txpow_6 = 0x06, // +17dBm .. 50mW + RFM22_tx_pwr_txpow_7 = 0x07 // +20dBm .. 100mW +}; + +enum rfm22b_datarate { + RFM22_datarate_500 = 0, + RFM22_datarate_1000 = 1, + RFM22_datarate_2000 = 2, + RFM22_datarate_4000 = 3, + RFM22_datarate_8000 = 4, + RFM22_datarate_9600 = 5, + RFM22_datarate_16000 = 6, + RFM22_datarate_19200 = 7, + RFM22_datarate_24000 = 8, + RFM22_datarate_32000 = 9, + RFM22_datarate_64000 = 10, + RFM22_datarate_128000 = 11, + RFM22_datarate_192000 = 12, + RFM22_datarate_256000 = 13, +}; + /* Public Functions */ extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg); -extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr); +extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr); +extern void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening); +extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay); diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 4719e722d..aa80f1b62 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -490,8 +490,8 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_deltasigma_adc_tuning1 0x67 // R/W #define RFM22_deltasigma_adc_tuning2 0x68 // R/W */ -#define RFM22_agc_override1 0x69 // R/W -#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. +#define RFM22_agc_override1 0x69 // R/W +#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. #define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0]. #define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB. #define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value. @@ -501,30 +501,22 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; //#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W //#define RFM22_gfsk_fir_coeff_value 0x6C // R/W -#define RFM22_tx_power 0x6D // R/W -#define RFM22_tx_pwr_txpow_0 0x00 // +1dBm .. 1.25mW -#define RFM22_tx_pwr_txpow_1 0x01 // +2dBm .. 1.6mW -#define RFM22_tx_pwr_txpow_2 0x02 // +5dBm .. 3.16mW -#define RFM22_tx_pwr_txpow_3 0x03 // +8dBm .. 6.3mW -#define RFM22_tx_pwr_txpow_4 0x04 // +11dBm .. 12.6mW -#define RFM22_tx_pwr_txpow_5 0x05 // +14dBm .. 25mW -#define RFM22_tx_pwr_txpow_6 0x06 // +17dBm .. 50mW -#define RFM22_tx_pwr_txpow_7 0x07 // +20dBm .. 100mW -#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. +#define RFM22_tx_power 0x6D // R/W +#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. #define RFM22_tx_pwr_papeaklvl_0 0x10 // " " #define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default #define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable. #define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency. -#define RFM22_tx_data_rate1 0x6E // R/W -#define RFM22_tx_data_rate0 0x6F // R/W +#define RFM22_tx_data_rate1 0x6E // R/W +#define RFM22_tx_data_rate0 0x6F // R/W #define RFM22_modulation_mode_control1 0x70 // R/W -#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. -#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. -#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. -#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). -#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. +#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. +#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. +#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. +#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). +#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. #define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps. #define RFM22_modulation_mode_control2 0x71 // R/W @@ -533,8 +525,8 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_mmc2_modtyp_ook 0x01 // #define RFM22_mmc2_modtyp_fsk 0x02 // #define RFM22_mmc2_modtyp_gfsk 0x03 // -#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". -#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. +#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". +#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. #define RFM22_mmc2_dtmod_mask 0x30 // Modulation source. #define RFM22_mmc2_dtmod_dm_gpio 0x00 // #define RFM22_mmc2_dtmod_dm_sdi 0x10 // From 2541affd806ea6e5fd0185c37cb9d439a261bfa1 Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Wed, 3 Oct 2012 20:03:35 -0700 Subject: [PATCH 495/508] RFM22B: Added back configuration of the RF Power and RF Datarate. Also added setting of the destination ID in the rfm22b driver. --- flight/Modules/Radio/radio.c | 115 ++++++++++++++--------------- flight/PiOS/Common/pios_rfm22b.c | 83 +++++++++++---------- flight/PiOS/inc/pios_rfm22b.h | 32 +++++++- flight/PiOS/inc/pios_rfm22b_priv.h | 34 ++++----- 4 files changed, 143 insertions(+), 121 deletions(-) diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index b5beb1359..8820e4081 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -185,69 +185,66 @@ static int32_t RadioInitialize(void) const struct pios_board_info * bdinfo = &pios_board_info_blob; pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - // Not appropriate for a constant struct. Is it necessary to make a local copy of the cfg? - // We should probably be consistent with other drivers and allocate a device structure with - // dynamical configuration in it -#if 0 - pios_rfm22b_cfg->frequencyHz = pipxSettings.Frequency; - pios_rfm22b_cfg->RFXtalCap = pipxSettings.FrequencyCalibration; - switch (pipxSettings.RFSpeed) - { - case PIPXSETTINGS_RFSPEED_2400: - pios_rfm22b_cfg->maxRFBandwidth = 2000; - break; - case PIPXSETTINGS_RFSPEED_4800: - pios_rfm22b_cfg->maxRFBandwidth = 4000; - break; - case PIPXSETTINGS_RFSPEED_9600: - pios_rfm22b_cfg->maxRFBandwidth = 9600; - break; - case PIPXSETTINGS_RFSPEED_19200: - pios_rfm22b_cfg->maxRFBandwidth = 19200; - break; - case PIPXSETTINGS_RFSPEED_38400: - pios_rfm22b_cfg->maxRFBandwidth = 32000; - break; - case PIPXSETTINGS_RFSPEED_57600: - pios_rfm22b_cfg->maxRFBandwidth = 64000; - break; - case PIPXSETTINGS_RFSPEED_115200: - pios_rfm22b_cfg->maxRFBandwidth = 128000; - break; - } - switch (pipxSettings.MaxRFPower) - { - case PIPXSETTINGS_MAXRFPOWER_125: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_0; - break; - case PIPXSETTINGS_MAXRFPOWER_16: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_1; - break; - case PIPXSETTINGS_MAXRFPOWER_316: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_2; - break; - case PIPXSETTINGS_MAXRFPOWER_63: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_3; - break; - case PIPXSETTINGS_MAXRFPOWER_126: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_4; - break; - case PIPXSETTINGS_MAXRFPOWER_25: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_5; - break; - case PIPXSETTINGS_MAXRFPOWER_50: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_6; - break; - case PIPXSETTINGS_MAXRFPOWER_100: - pios_rfm22b_cfg->maxTxPower = RFM22_tx_pwr_txpow_7; - break; - } -#endif - /* Initalize the RFM22B radio COM device. */ if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) return -1; + // Set the maximum radio RF power. + switch (pipxSettings.MaxRFPower) + { + case PIPXSETTINGS_MAXRFPOWER_125: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); + break; + case PIPXSETTINGS_MAXRFPOWER_16: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); + break; + case PIPXSETTINGS_MAXRFPOWER_316: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); + break; + case PIPXSETTINGS_MAXRFPOWER_63: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); + break; + case PIPXSETTINGS_MAXRFPOWER_126: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); + break; + case PIPXSETTINGS_MAXRFPOWER_25: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); + break; + case PIPXSETTINGS_MAXRFPOWER_50: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); + break; + case PIPXSETTINGS_MAXRFPOWER_100: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); + break; + } + + switch (pipxSettings.RFSpeed) { + case PIPXSETTINGS_RFSPEED_2400: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_2000, true); + break; + case PIPXSETTINGS_RFSPEED_4800: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_4000, true); + break; + case PIPXSETTINGS_RFSPEED_9600: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_9600, true); + break; + case PIPXSETTINGS_RFSPEED_19200: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_19200, true); + break; + case PIPXSETTINGS_RFSPEED_38400: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_32000, true); + break; + case PIPXSETTINGS_RFSPEED_57600: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_64000, true); + break; + case PIPXSETTINGS_RFSPEED_115200: + RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_128000, true); + break; + } + + // Set the radio destination ID. + PIOS_RFM22B_SetDestinationId(pios_rfm22b_id, pipxSettings.PairID); + // Initialize the packet handler PacketHandlerConfig pios_ph_cfg = { .default_destination_id = 0xffffffff, // Broadcast diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 96d735d61..bd3925f03 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -62,6 +62,7 @@ #define ISR_TIMEOUT 5 // ms #define EVENT_QUEUE_SIZE 5 #define PACKET_QUEUE_SIZE 3 +#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_64000 // The maximum amount of time without activity before initiating a reset. #define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms @@ -164,8 +165,12 @@ struct pios_rfm22b_dev { uint32_t spi_id; uint32_t slave_num; + // The device ID uint32_t deviceID; + // The destination ID + uint32_t destination_id; + // The task handle xTaskHandle taskHandle; @@ -184,6 +189,9 @@ struct pios_rfm22b_dev { // the transmit power to use for data transmissions uint8_t tx_power; + // The RF datarate lookup index. + uint8_t datarate; + // The state machine state and the current event enum pios_rfm22b_state state; // The event queue handle @@ -558,6 +566,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Bind the configuration to the device instance rfm22b_dev->cfg = *cfg; + rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE; // Initialize the packets. rfm22b_dev->rx_packet = NULL; @@ -570,7 +579,6 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu g_rfm22b_dev = rfm22b_dev; // Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet. - rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(rfm22b_dev->cfg.maxRFBandwidth) + 0.5); rfm22b_dev->packet_start_ticks = 0; // Create a semaphore to know if an ISR needs responding to @@ -672,24 +680,20 @@ uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id) return 0; } -void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr) +void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; if(!PIOS_RFM22B_validate(rfm22b_dev)) return; + rfm22b_dev->tx_power = tx_pwr; +} - switch (tx_pwr) - { - case 0: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW - case 1: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW - case 2: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW - case 3: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW - case 4: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW - case 5: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW - case 6: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW - case 7: rfm22b_dev->tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW - default: break; - } +void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return; + rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id; } int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) @@ -1120,42 +1124,41 @@ uint32_t rfm22_freqHopSize(void) // // This gives 2(45 + 9.6) = 109.2kHz. -void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) +void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening) { + struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return; - // Find the closest data rate that is >= the value passed in - int lookup_index = 0; - while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps) - lookup_index++; - lookup_index = 10; - - datarate_bps = data_rate[lookup_index]; + uint32_t datarate_bps = data_rate[datarate]; + rfm22b_dev->datarate = datarate; + rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5); // rfm22_if_filter_bandwidth - rfm22_write(0x1C, reg_1C[lookup_index]); + rfm22_write(0x1C, reg_1C[datarate]); // rfm22_afc_loop_gearshift_override - rfm22_write(0x1D, reg_1D[lookup_index]); + rfm22_write(0x1D, reg_1D[datarate]); // RFM22_afc_timing_control - rfm22_write(0x1E, reg_1E[lookup_index]); + rfm22_write(0x1E, reg_1E[datarate]); // RFM22_clk_recovery_gearshift_override - rfm22_write(0x1F, reg_1F[lookup_index]); + rfm22_write(0x1F, reg_1F[datarate]); // rfm22_clk_recovery_oversampling_ratio - rfm22_write(0x20, reg_20[lookup_index]); + rfm22_write(0x20, reg_20[datarate]); // rfm22_clk_recovery_offset2 - rfm22_write(0x21, reg_21[lookup_index]); + rfm22_write(0x21, reg_21[datarate]); // rfm22_clk_recovery_offset1 - rfm22_write(0x22, reg_22[lookup_index]); + rfm22_write(0x22, reg_22[datarate]); // rfm22_clk_recovery_offset0 - rfm22_write(0x23, reg_23[lookup_index]); + rfm22_write(0x23, reg_23[datarate]); // rfm22_clk_recovery_timing_loop_gain1 - rfm22_write(0x24, reg_24[lookup_index]); + rfm22_write(0x24, reg_24[datarate]); // rfm22_clk_recovery_timing_loop_gain0 - rfm22_write(0x25, reg_25[lookup_index]); + rfm22_write(0x25, reg_25[datarate]); // rfm22_afc_limiter - rfm22_write(0x2A, reg_2A[lookup_index]); + rfm22_write(0x2A, reg_2A[datarate]); /* This breaks all bit rates < 100000! if (datarate_bps < 100000) @@ -1167,9 +1170,9 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) */ // rfm22_tx_data_rate1 - rfm22_write(0x6E, reg_6E[lookup_index]); + rfm22_write(0x6E, reg_6E[datarate]); // rfm22_tx_data_rate0 - rfm22_write(0x6F, reg_6F[lookup_index]); + rfm22_write(0x6F, reg_6F[datarate]); // Enable data whitening // uint8_t txdtrtscale_bit = rfm22_read(RFM22_modulation_mode_control1) & RFM22_mmc1_txdtrtscale; @@ -1177,16 +1180,16 @@ void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening) if (!data_whitening) // rfm22_modulation_mode_control1 - rfm22_write(0x70, reg_70[lookup_index] & ~RFM22_mmc1_enwhite); + rfm22_write(0x70, reg_70[datarate] & ~RFM22_mmc1_enwhite); else // rfm22_modulation_mode_control1 - rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite); + rfm22_write(0x70, reg_70[datarate] | RFM22_mmc1_enwhite); // rfm22_modulation_mode_control2 - rfm22_write(0x71, reg_71[lookup_index]); + rfm22_write(0x71, reg_71[datarate]); // rfm22_frequency_deviation - rfm22_write(0x72, reg_72[lookup_index]); + rfm22_write(0x72, reg_72[datarate]); rfm22_write(RFM22_ook_counter_value1, 0x00); rfm22_write(RFM22_ook_counter_value2, 0x00); @@ -1850,7 +1853,7 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22_setFreqCalibration(rfm22b_dev->cfg.RFXtalCap); rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->cfg.frequencyHz); - rfm22_setDatarate(rfm22b_dev->cfg.maxRFBandwidth, true); + RFM22_SetDatarate((uint32_t)rfm22b_dev, rfm22b_dev->datarate, true); return RFM22B_EVENT_INITIALIZED; } diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 451480960..65c823283 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -49,9 +49,39 @@ struct pios_rfm22b_cfg { enum gpio_direction gpio_direction; }; +enum rfm22b_tx_power { + RFM22_tx_pwr_txpow_0 = 0x00, // +1dBm .. 1.25mW + RFM22_tx_pwr_txpow_1 = 0x01, // +2dBm .. 1.6mW + RFM22_tx_pwr_txpow_2 = 0x02, // +5dBm .. 3.16mW + RFM22_tx_pwr_txpow_3 = 0x03, // +8dBm .. 6.3mW + RFM22_tx_pwr_txpow_4 = 0x04, // +11dBm .. 12.6mW + RFM22_tx_pwr_txpow_5 = 0x05, // +14dBm .. 25mW + RFM22_tx_pwr_txpow_6 = 0x06, // +17dBm .. 50mW + RFM22_tx_pwr_txpow_7 = 0x07 // +20dBm .. 100mW +}; + +enum rfm22b_datarate { + RFM22_datarate_500 = 0, + RFM22_datarate_1000 = 1, + RFM22_datarate_2000 = 2, + RFM22_datarate_4000 = 3, + RFM22_datarate_8000 = 4, + RFM22_datarate_9600 = 5, + RFM22_datarate_16000 = 6, + RFM22_datarate_19200 = 7, + RFM22_datarate_24000 = 8, + RFM22_datarate_32000 = 9, + RFM22_datarate_64000 = 10, + RFM22_datarate_128000 = 11, + RFM22_datarate_192000 = 12, + RFM22_datarate_256000 = 13, +}; + /* Public Functions */ extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, uint32_t spi_id, uint32_t slave_num, const struct pios_rfm22b_cfg *cfg); -extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, uint8_t tx_pwr); +extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr); +extern void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening); +extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay); diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 4719e722d..aa80f1b62 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -490,8 +490,8 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_deltasigma_adc_tuning1 0x67 // R/W #define RFM22_deltasigma_adc_tuning2 0x68 // R/W */ -#define RFM22_agc_override1 0x69 // R/W -#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. +#define RFM22_agc_override1 0x69 // R/W +#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. #define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0]. #define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB. #define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value. @@ -501,30 +501,22 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; //#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W //#define RFM22_gfsk_fir_coeff_value 0x6C // R/W -#define RFM22_tx_power 0x6D // R/W -#define RFM22_tx_pwr_txpow_0 0x00 // +1dBm .. 1.25mW -#define RFM22_tx_pwr_txpow_1 0x01 // +2dBm .. 1.6mW -#define RFM22_tx_pwr_txpow_2 0x02 // +5dBm .. 3.16mW -#define RFM22_tx_pwr_txpow_3 0x03 // +8dBm .. 6.3mW -#define RFM22_tx_pwr_txpow_4 0x04 // +11dBm .. 12.6mW -#define RFM22_tx_pwr_txpow_5 0x05 // +14dBm .. 25mW -#define RFM22_tx_pwr_txpow_6 0x06 // +17dBm .. 50mW -#define RFM22_tx_pwr_txpow_7 0x07 // +20dBm .. 100mW -#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. +#define RFM22_tx_power 0x6D // R/W +#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. #define RFM22_tx_pwr_papeaklvl_0 0x10 // " " #define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default #define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable. #define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency. -#define RFM22_tx_data_rate1 0x6E // R/W -#define RFM22_tx_data_rate0 0x6F // R/W +#define RFM22_tx_data_rate1 0x6E // R/W +#define RFM22_tx_data_rate0 0x6F // R/W #define RFM22_modulation_mode_control1 0x70 // R/W -#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. -#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. -#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. -#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). -#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. +#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. +#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. +#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. +#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). +#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. #define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps. #define RFM22_modulation_mode_control2 0x71 // R/W @@ -533,8 +525,8 @@ extern const struct pios_com_driver pios_rfm22b_com_driver; #define RFM22_mmc2_modtyp_ook 0x01 // #define RFM22_mmc2_modtyp_fsk 0x02 // #define RFM22_mmc2_modtyp_gfsk 0x03 // -#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". -#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. +#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". +#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. #define RFM22_mmc2_dtmod_mask 0x30 // Modulation source. #define RFM22_mmc2_dtmod_dm_gpio 0x00 // #define RFM22_mmc2_dtmod_dm_sdi 0x10 // From 193fdcd9a2a722ddba64e676e7d02a31b0e460ac Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 4 Oct 2012 16:41:02 -0500 Subject: [PATCH 496/508] Make the default PipX RF power 1.25 mW to avoid damanging anything when there is no antenna --- shared/uavobjectdefinition/pipxsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/pipxsettings.xml b/shared/uavobjectdefinition/pipxsettings.xml index 52524aa22..af0927add 100644 --- a/shared/uavobjectdefinition/pipxsettings.xml +++ b/shared/uavobjectdefinition/pipxsettings.xml @@ -9,7 +9,7 @@ - + From 82efb91fadfc0656027f153afda25073698b5169 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 4 Oct 2012 16:46:16 -0500 Subject: [PATCH 497/508] Add developer GCS config layout --- .../default_configurations/Developer.xml | 2848 +++++++++++++++++ 1 file changed, 2848 insertions(+) create mode 100644 ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml new file mode 100644 index 000000000..cc57ea641 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/Developer.xml @@ -0,0 +1,2848 @@ + + + true + true + Developer +

Developer mode configuration
+ true + OPMapGadget + default + en_US + true + 628 + 697 + default + false + + + + + 1 + 0 + + 1 + + + + 0 + + + #666666 + false + true + + + 91 + 90 + 89 + 88 + 87 + 86 + 100 + + + + + false + 1.0.0 + + + + + default + Accels + 0 + false + + -1 + 0 + 0 + + + + %%DATAPATH%%sounds + + 0 + + 1 + + false + + 0 + + + + + + 57600 + + + + + + false + 0.0.0 + + + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/attitude.svg + foreground + needle + needle + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + AttitudeActual + 75 + 20 + 0 + Vertical + Pitch + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/altimeter.svg + foreground + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 10 + 0 + Rotate + Altitude + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/barometer.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 10 + 1120 + 1000 + Rotate + Pressure + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/vsi.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + VelocityActual + 0.01 + 12 + -12 + Rotate + Down + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/compass.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Yaw + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/attitude.svg + foreground + needle + needle + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + AttitudeActual + 75 + 20 + 0 + Vertical + Pitch + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/altimeter.svg + foreground + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 10 + 0 + Rotate + Altitude + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/barometer.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 10 + 1120 + 1000 + Rotate + Pressure + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/vsi.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + VelocityActual + 0.01 + 11.2 + -11.2 + Rotate + Down + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/compass.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Yaw + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/speed.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + GPSPosition + 3.6 + 120 + 0 + Rotate + Groundspeed + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/deluxe/thermometer.svg + foreground + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 120 + 0 + Rotate + Temperature + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + /home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg + foreground + needle + needle2 + needle2 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + Accels + 1 + 20 + -20 + Horizontal + x + Accels + -1 + 360 + 0 + Rotate + x + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/speed.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + GPSPosition + 3.6 + 120 + 0 + Rotate + Groundspeed + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/attitude.svg + foreground + needle + needle + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + AttitudeActual + 75 + 20 + 0 + Vertical + Pitch + AttitudeActual + -1 + 360 + 0 + Rotate + Roll + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/altimeter.svg + foreground + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 10 + 0 + Rotate + Altitude + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/barometer.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 10 + 1120 + 1000 + Rotate + Pressure + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/vsi.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + VelocityActual + 0.01 + 12 + -12 + Rotate + Down + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/compass.svg + foreground + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + AttitudeActual + -1 + 360 + 0 + Rotate + Yaw + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/speed.svg + + needle + + + Lucida Grande,13,-1,5,50,0,0,0,0,0 + GPSPosition + 3.6 + 120 + 0 + Rotate + Groundspeed + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/hi-contrast/thermometer.svg + + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 120 + 0 + Rotate + Temperature + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/thermometer.svg + + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + ManualControlCommand + 1 + 2000 + 1000 + Rotate + Channel-3 + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + false + 0.0.0 + + + false + background + %%DATAPATH%%dials/default/thermometer.svg + + needle + needle2 + needle3 + Lucida Grande,13,-1,5,50,0,0,0,0,0 + BaroAltitude + 1 + 120 + 0 + Rotate + Temperature + BaroAltitude + 1 + 100 + 0 + Rotate + Altitude + BaroAltitude + 1 + 1000 + 0 + Rotate + Altitude + false + + + + + + + false + 0.0.0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.1 + 3 + 0 + 0.1 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + false + false + true + false + false + false + false + false + + 0 + 2 + 1 + 0 + 2 + 3 + + + + + + + false + 0.0.0 + + + Telemetry + 3 + 0 + 0 + /dev/cu.Bluetooth-Modem + 11 + 0 + + + + + false + 0.0.0 + + + Serial + 3 + 0 + 0 + /dev/cu.Bluetooth-Modem + 17 + 0 + + + + + + + false + 0.0.0 + + + \usr\games\fgfs + \usr\share\games\FlightGear + 127.0.0.1 + 9009 + + + false + 9010 + 127.0.0.1 + FG + true + + + + + false + 0.0.0 + + + \home\lafargue\X-Plane 9\X-Plane-i686 + \usr\share\games\FlightGear + 127.0.0.3 + 6756 + + + false + 49000 + 127.0.0.1 + X-Plane + false + + + + + + + false + 0.0.0 + + + false + false + true + true + true + 20 + + + true + 200 + true + 0 + true + 127.0.0.1 + 40100 + true + false + false + 40200 + 20 + 127.0.0.1 + ASimRC + 50 + false + @Variant(AAAAh0CgAAA=) + + + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg + 2 + 1 + Andale Mono,8,-1,5,50,0,0,0,0,0 + -9 + -10 + 11 + -11 + 11 + -11 + Accels + x + false + -5 + -11 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg + 2 + 1 + Andale Mono,6,-1,5,50,0,0,0,0,0 + -9 + -10 + 11 + -11 + 11 + -11 + Accels + y + false + -5 + -11 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg + 2 + 1 + Andale Mono,8,-1,5,50,0,0,0,0,0 + -9 + -10 + 11 + -11 + 11 + -11 + Accels + z + false + -5 + -11 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/default/arm-status.svg + 0 + 1 + ,12,-1,5,50,0,0,0,0,0 + 100 + 66 + 100 + 0 + 33 + 0 + FlightStatus + Armed + false + 66 + 33 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/default/textonly.svg + 0 + 0.001 + ,12,-1,5,50,0,0,0,0,0 + 100 + 66 + 100 + 0 + 33 + 0 + SystemStats + FlightTime + false + 66 + 33 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/default/flightmode-status.svg + 0 + 1 + ,12,-1,5,50,0,0,0,0,0 + 100 + 66 + 100 + 0 + 33 + 0 + FlightStatus + FlightMode + false + 66 + 33 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/default/gps-signal.svg + 0 + 1 + ,12,-1,5,50,0,0,0,0,0 + 0 + 0 + 12 + 0 + 0 + 0 + GPSPosition + Satellites + false + 0 + 0 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/default/gps-status.svg + 0 + 1 + ,12,-1,5,50,0,0,0,0,0 + 100 + 66 + 100 + 0 + 33 + 0 + GPSPosition + Status + false + 66 + 33 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 0 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 90 + 0 + 100 + 0 + 100 + 95 + SystemStats + CPULoad + false + 95 + 90 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ActuatorDesired + Pitch + false + 0.8 + -0.8 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ManualControlCommand + Pitch + false + 0.8 + -0.8 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.8 + 0.3 + 90 + -90 + 1 + 0 + AttitudeActual + Pitch + false + 0.9 + 0.1 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ActuatorDesired + Roll + false + 0.8 + -0.8 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ManualControlCommand + Roll + false + 0.8 + -0.8 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg + 0 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 650 + 0 + 1200 + 0 + 1200 + 900 + GCSTelemetryStats + RxDataRate + false + 900 + 650 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg + 0 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 650 + 0 + 1200 + 0 + 1200 + 900 + GCSTelemetryStats + TxDataRate + false + 900 + 650 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + 0 + 1 + 0 + 1 + 0.75 + ManualControlCommand + Throttle + false + 0.75 + 0.5 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ActuatorDesired + Yaw + false + 0.8 + -0.8 + + + + + false + 0.0.0 + + + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg + 2 + 1 + Andale Mono,12,-1,5,75,0,0,0,0,0 + 0.5 + -0.5 + 1 + -1 + 1 + -1 + ManualControlCommand + Yaw + false + 0.8 + -0.8 + + + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/boards/CC3D/CC3D.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/boards/CopterControl/CopterControl.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/planes/Easystar/easystar.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/planes/firecracker/firecracker.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/planes/funjet/funjet.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/joes_cnc/J14-Q_+.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/joes_cnc/J14-Q_X.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/joes_cnc/J14-QT_+.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/joes_cnc/J14-QT_X.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/ricoo/ricoo.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/test_quad/test_quad_+.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/test_quad/test_quad_X.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + + + + + + false + 0.0.0 + + + ServerAndCache + %%STOREPATH%%mapscache/ + 0 + 0 + 2 + GoogleSatellite + 2000 + 1 + false + mapquad.png + true + false + + + + + false + 0.0.0 + + + CacheOnly + %%STOREPATH%%mapscache/ + 0 + 0 + 2 + GoogleMap + 2000 + 1 + false + airplanepip.png + true + false + + + + + false + 0.0.0 + + + ServerAndCache + %%STOREPATH%%mapscache/ + 29.97 + 95.35 + 7 + GoogleMap + 2000 + 1 + false + mapquad.png + true + true + + + + + + + false + 0.0.0 + + + false + %%DATAPATH%%pfd/default/pfd.svg + false + false + + + + + false + 0.0.0 + + + true + %%DATAPATH%%pfd/default/pfd.svg + false + false + + + + + + + false + 0.0.0 + + + false + 2000 + false + %%DATAPATH%%pfd/default/readymap.earth + 46.6715 + 10.1589 + true + %%DATAPATH%%pfd/default/Pfd.qml + false + + + + + false + 0.0.0 + + + false + 2000 + false + %%DATAPATH%%pfd/default/readymap.earth + 46.6715 + 10.1589 + true + %%DATAPATH%%pfd/default/Pfd.qml + false + + + + + + + false + 0.0.0 + + + Unknown + true + + + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4294901760 + None + x + Accels + 0 + 1 + 6.92920863607354e-310 + 0 + + + 4283782655 + None + y + Accels + 1.78017180972965e-306 + 1 + 9.34609790258712e-307 + 0 + + + 4283804160 + None + z + Accels + 2.6501977682312e-318 + 1 + 6.92920723246466e-310 + 0 + + 3 + 1 + 100 + + + + + false + 0.0.0 + + + false + false + + 1000 + 20 + + 4294901760 + None + Channel-4 + ActuatorCommand + 1.72723371101889e-77 + 1 + 6.02760087926321e-322 + 0 + + + 4294901760 + None + Channel-5 + ActuatorCommand + 3.55727265005698e-322 + 1 + 2.19822614387826e-314 + 0 + + + 4289374847 + None + Channel-6 + ActuatorCommand + 1.72723371101889e-77 + 1 + 1.72723371101889e-77 + 0 + + + 4289374847 + None + Channel-7 + ActuatorCommand + 6.92916505779426e-310 + 1 + 4.22277162500408e-312 + 0 + + 4 + 1 + 100 + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4283760895 + None + Roll + AttitudeActual + 6.92921152826347e-310 + 1 + 6.92921152826031e-310 + 0 + + + 4278233600 + None + Yaw + AttitudeActual + 0 + 1 + 0 + 0 + + + 4294901760 + None + Pitch + AttitudeActual + 0 + 1 + 0 + 0 + + 3 + 1 + 100 + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4278190080 + None + Pressure + BaroAltitude + 1.72723371102043e-77 + 1 + 3.86203233966055e-312 + 0 + + 1 + 1 + 1000 + + + + + false + 0.0.0 + + + false + false + + 1000 + 40 + + 4278190207 + None + Channel-1 + ManualControlCommand + 0 + 1 + 0 + 0 + + + 4294901760 + None + Channel-4 + ManualControlCommand + 6.92916505599784e-310 + 1 + 7.21478569792807e-313 + 0 + + + 4294901760 + None + Channel-5 + ManualControlCommand + 8.34448532677451e-308 + 1 + 1.78019353780608e-306 + 0 + + + 4294901760 + None + Channel-6 + ManualControlCommand + 6.9291650571421e-310 + 1 + 4.22277162500408e-312 + 0 + + + 4294901760 + None + Channel-7 + ManualControlCommand + 4.24399158193054e-314 + 1 + 4.172013484701e-309 + 0 + + + 4283825920 + None + Channel-2 + ManualControlCommand + 1.72723371101889e-77 + 1 + 2.48782786590693e-310 + 0 + + + 4294923520 + None + Channel-3 + ManualControlCommand + 6.92921442541857e-310 + 1 + 6.92921441189619e-310 + 0 + + + 4294967040 + None + Channel-0 + ManualControlCommand + 6.92921439506975e-310 + 1 + 1.72723371101889e-77 + 0 + + 8 + 1 + 200 + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4294901760 + None + x + Accels + 0 + 1 + 0 + 0 + + + 4283782655 + None + y + Accels + 0 + 1 + 0 + 0 + + + 4283804160 + None + z + Accels + 0 + 1 + 0 + 0 + + 3 + 1 + 500 + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4283804160 + None + z + Gyros + 1.02360527502876e-306 + 1 + 6.92921152846347e-310 + 0 + + + 4283782655 + None + y + Gyros + 0 + 1 + 0 + 0 + + + 4294901760 + None + x + Gyros + 0 + 1 + 0 + 0 + + 3 + 1 + 500 + + + + + false + 0.0.0 + + + false + false + + 1000 + 60 + + 4294901760 + None + x + Magnetometer + 6.92916505601691e-310 + 1 + 3.86203233966055e-312 + 0 + + + 4283782655 + None + y + Magnetometer + 1.72723371101889e-77 + 1 + -1 + 0 + + + 4283804160 + None + z + Magnetometer + 1.72723371102028e-77 + 1 + 7.21478569792807e-313 + 0 + + 3 + 1 + 500 + + + + + false + 0.0.0 + + + false + false + + 1000 + 240 + + 4294945280 + None + StackRemaining-System + TaskInfo + 1.02360527502876e-306 + 1 + 6.92921153577169e-310 + 0 + + + 4294945280 + None + StackRemaining-Actuator + TaskInfo + 0 + 1 + 0 + 0 + + + 4294945280 + None + StackRemaining-Guidance + TaskInfo + 6.92921442421083e-310 + 1 + -1.29073709209104e-231 + 0 + + + 4294945280 + None + StackRemaining-Watchdog + TaskInfo + 6.92920724098472e-310 + 1 + 3.91299991506267e-321 + 0 + + + 4294945280 + None + StackRemaining-TelemetryTx + TaskInfo + 0 + 1 + 0 + 0 + + + 4294945280 + None + StackRemaining-TelemetryTxPri + TaskInfo + 1.72723371101889e-77 + 1 + 1.72723371101889e-77 + 0 + + + 4294945280 + None + StackRemaining-TelemetryRx + TaskInfo + 6.92921438535612e-310 + 1 + 1.72723371101889e-77 + 0 + + + 4294945280 + None + StackRemaining-GPS + TaskInfo + 1.72723371101889e-77 + 1 + 1.03979250816176e-312 + 0 + + + 4294945280 + None + StackRemaining-ManualControl + TaskInfo + 6.92921438705062e-310 + 1 + 6.92921152810932e-310 + 0 + + + 4294945280 + None + StackRemaining-Altitude + TaskInfo + 7.4109846876187e-323 + 1 + 1.72723371101889e-77 + 0 + + + 4294945280 + None + StackRemaining-AHRSComms + TaskInfo + 5.43472210425371e-323 + 1 + 1.72723371101889e-77 + 0 + + + 4294945280 + None + StackRemaining-Stabilization + TaskInfo + 1.72723371101889e-77 + 1 + 1.72723371101889e-77 + 0 + + 12 + 1 + 1000 + + + + + false + 0.0.0 + + + false + false + + 1000 + 20 + + 4289374847 + None + TxFailures + GCSTelemetryStats + 0 + 1 + 0 + 0 + + + 4283782655 + None + RxFailures + GCSTelemetryStats + 0 + 1 + 0 + 0 + + + 4294901760 + None + TxRetries + GCSTelemetryStats + 0 + 1 + 0 + 0 + + 3 + 1 + 100 + + + + + false + 0.0.0 + + + false + false + + 1000 + 240 + + 4294945407 + None + FlightTime + SystemStats + 1.02360527502876e-306 + 1 + 6.92921153586022e-310 + 0 + + + 0 + + + + 0 + 1 + 0 + 0 + + 2 + 1 + 800 + + + + + + + false + 0.0.0 + + + %%DATAPATH%%diagrams/default/system-health.svg + + + + + + + false + 0.0.0 + + + false + false + #5baa56 + false + #ff7957 + 500 + false + + + + + + + false + 0.0.0 + + + 3 + 0 + 0 + /dev/ttyS0 + 14 + 0 + + + + + false + 1.2.0 + + + + + false + + + + + + LineardialGadget + + Flight Time + + uavGadget + + + + LineardialGadget + + Arm Status + + uavGadget + + + LineardialGadget + + Flight mode + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7) + splitter + + 1 + @Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf) + splitter + + + PFDGadget + + raw + + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4) + splitter + + + + ModelViewGadget + + Test Quad X + + uavGadget + + + SystemHealthGadget + + default + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV) + splitter + + 2 + @Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf) + splitter + + + OPMapGadget + + Google Sat + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp) + splitter + + UAVGadgetManagerV1 + + + false + + + ConfigGadget + + default + + uavGadget + + + UAVObjectBrowser + + default + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAADRgAAAAIAAAJV) + splitter + + UAVGadgetManagerV1 + + + false + + + UAVObjectBrowser + + default + + uavGadget + + + + + LoggingGadget + uavGadget + + + GpsDisplayGadget + + Flight GPS + + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo) + splitter + + + DebugGadget + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp) + splitter + + 1 + @Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo) + splitter + + UAVGadgetManagerV1 + + + false + + + + ScopeGadget + + Accel + + uavGadget + + + ScopeGadget + + Raw Gyros + + uavGadget + + 2 + @Variant(AAAACQAAAAA=) + splitter + + + + ScopeGadget + + Attitude + + uavGadget + + + ScopeGadget + + Uptimes + + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAAClQAAAAIAAAB3) + splitter + + 1 + @Variant(AAAACQAAAAIAAAACAAACjQAAAAIAAAKU) + splitter + + UAVGadgetManagerV1 + + + false + + + + HITL + + XPlane HITL + + uavGadget + + + HITLv2 + + default + + uavGadget + + 1 + @Variant(AAAACQAAAAA=) + splitter + + + + EmptyGadget + uavGadget + + + GCSControlGadget + + MS Sidewinder + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC) + splitter + + 2 + @Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ) + splitter + + UAVGadgetManagerV1 + + + false + + + Uploader + + default + + uavGadget + + + + + LineardialGadget + + Flight Time + + uavGadget + + + SystemHealthGadget + + default + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAABQgAAAAIAAAGM) + splitter + + + PFDGadget + + raw + + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf) + splitter + + 1 + @Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK) + splitter + + UAVGadgetManagerV1 + + + + false + :/core/images/ah.png + :/core/images/openpilot_logo_64.png + :/core/images/config.png + :/core/images/cog.png + :/core/images/scopes.png + :/core/images/joystick.png + :/core/images/cpu.png + :/core/images/openpilot_logo_64.png + :/core/images/openpilot_logo_64.png + :/core/images/openpilot_logo_64.png + 6 + 1 + Flight data + Workspace10 + Configuration + System + Scopes + HITL + Firmware + Workspace7 + Workspace8 + Workspace9 + + From 5724fa083c77f1f94d1b53b27583db5d5f00fffe Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Thu, 4 Oct 2012 21:11:40 -0700 Subject: [PATCH 498/508] RFM22B: Added link quality calculation based on number of dropped packets. Also added packet error correction, which apparently wasn't being done before. --- flight/Libraries/inc/packet_handler.h | 6 +- flight/Libraries/packet_handler.c | 165 ++---------------- flight/Modules/Radio/radio.c | 14 +- .../Modules/RadioComBridge/RadioComBridge.c | 2 +- flight/PiOS/Common/pios_rfm22b.c | 139 +++++++++++++-- flight/PiOS/inc/pios_rfm22b.h | 5 +- .../plugins/config/configpipxtremewidget.cpp | 4 +- .../src/plugins/config/pipxtreme.ui | 6 +- shared/uavobjectdefinition/pipxstatus.xml | 3 +- 9 files changed, 148 insertions(+), 196 deletions(-) diff --git a/flight/Libraries/inc/packet_handler.h b/flight/Libraries/inc/packet_handler.h index 1a4785842..c2cf0639a 100644 --- a/flight/Libraries/inc/packet_handler.h +++ b/flight/Libraries/inc/packet_handler.h @@ -60,8 +60,7 @@ typedef struct { uint32_t source_id; uint8_t type; uint8_t data_size; - uint8_t tx_seq; - uint8_t rx_seq; + uint16_t seq_num; } PHPacketHeader; #define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY) @@ -116,8 +115,7 @@ PHPacketHandle PHGetTXPacket(PHInstHandle h); void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p); uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p); uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len); -int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len); -uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error); +uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p); #endif // __PACKET_HANDLER_H__ diff --git a/flight/Libraries/packet_handler.c b/flight/Libraries/packet_handler.c index 9226c74ae..c2b54c54f 100644 --- a/flight/Libraries/packet_handler.c +++ b/flight/Libraries/packet_handler.c @@ -43,7 +43,6 @@ typedef struct { PHPacket *rx_packets; uint8_t rx_win_start; uint8_t rx_win_end; - uint16_t tx_seq_id; xSemaphoreHandle lock; PHOutputStream output_stream; PHDataHandler data_handler; @@ -52,8 +51,6 @@ typedef struct { } PHPacketData, *PHPacketDataHandle; // Private functions -static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p); -static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p); static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p); /** @@ -71,7 +68,6 @@ PHInstHandle PHInitialize(PacketHandlerConfig *cfg) if (!data) return 0; data->cfg = *cfg; - data->tx_seq_id = 0; // Allocate the packet windows data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.win_size); @@ -318,40 +314,6 @@ uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len) return PHLTransmitPacket(data, p); } -/** - * Verify that a buffer contains a valid packet. - * \param[in] h The packet handler instance data pointer. - * \param[in] p A pointer to the packet buffer. - * \param[in] received_len The length of data received. - * \return < 0 Failure - * \return > 0 Number of bytes consumed. - */ -int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len) -{ - - // Verify the packet length. - // Note: The last two bytes should be the RSSI and AFC. - uint16_t len = PHPacketSizeECC(p); - if (received_len < (len + 2)) - { - DEBUG_PRINTF(1, "Packet length error %d %d\n\r", received_len, len + 2); - return -1; - } - - // Attempt to correct any errors in the packet. - decode_data((unsigned char*)p, len); - - // Check that there were no unfixed errors. - bool rx_error = check_syndrome() != 0; - if(rx_error) - { - DEBUG_PRINTF(1, "Error in packet\n\r"); - return -2; - } - - return len + 2; -} - /** * Process a packet that has been received. * \param[in] h The packet handler instance data pointer. @@ -360,7 +322,7 @@ int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len) * \return 0 Failure * \return 1 Success */ -uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error) +uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p) { PHPacketDataHandle data = (PHPacketDataHandle)h; uint16_t len = PHPacketSizeECC(p); @@ -373,81 +335,23 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error) case PACKET_TYPE_STATUS: - if (!rx_error) - - // Pass on the channels to the status handler. - if(data->status_handler) - data->status_handler((PHStatusPacketHandle)p, rssi, afc); - + // Pass on the channels to the status handler. + if(data->status_handler) + data->status_handler((PHStatusPacketHandle)p, rssi, afc); break; - case PACKET_TYPE_ACKED_DATA: - - // Send the ACK / NACK - if (rx_error) - { - DEBUG_PRINTF(1, "Sending NACK\n\r"); - PHLSendNAck(data, p); - } - else - { - - PHLSendAck(data, p); - - // Pass on the data. - if(data->data_handler) - data->data_handler(p->data, p->header.data_size, rssi, afc); - } - - break; - - case PACKET_TYPE_ACK: - { - // Find the packet ID in the TX buffer, and free it. - unsigned int i = 0; - for (unsigned int i = 0; i < data->cfg.win_size; ++i) - if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) - PHReleaseTXPacket(h, data->tx_packets + i); -#ifdef DEBUG_LEVEL - if (i == data->cfg.win_size) - DEBUG_PRINTF(1, "Error finding acked packet to release\n\r"); -#endif - } - break; - - case PACKET_TYPE_NACK: - { - // Resend the packet. - unsigned int i = 0; - for ( ; i < data->cfg.win_size; ++i) - if (data->tx_packets[i].header.tx_seq == p->header.rx_seq) - PHLTransmitPacket(data, data->tx_packets + i); -#ifdef DEBUG_LEVEL - if (i == data->cfg.win_size) - DEBUG_PRINTF(1, "Error finding acked packet to NACK\n\r"); - DEBUG_PRINTF(1, "Resending after NACK\n\r"); -#endif - } - break; - case PACKET_TYPE_PPM: - if (!rx_error) - - // Pass on the channels to the PPM handler. - if(data->ppm_handler) - data->ppm_handler(((PHPpmPacketHandle)p)->channels); - + // Pass on the channels to the PPM handler. + if(data->ppm_handler) + data->ppm_handler(((PHPpmPacketHandle)p)->channels); break; case PACKET_TYPE_DATA: - if (!rx_error) - - // Pass on the data to the data handler. - if(data->data_handler) - data->data_handler(p->data, p->header.data_size, rssi, afc); - + // Pass on the data to the data handler. + if(data->data_handler) + data->data_handler(p->data, p->header.data_size, rssi, afc); break; default: @@ -473,58 +377,9 @@ static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p) if(!data->output_stream) return 0; - // Set the sequence ID to the current ID. - p->header.tx_seq = data->tx_seq_id++; - p->header.source_id = data->cfg.source_id; - - // Add the error correcting code. - encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); - // Transmit the packet using the output stream. if(data->output_stream(p) == -1) return 0; return 1; } - -/** - * Send an ACK packet. - * \param[in] data The packet handler instance data pointer. - * \param[in] p A pointer to the packet buffer of the packet to be ACKed. - * \return 1 Success - * \return 0 Failure - */ -static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p) -{ - - // Create the ACK message - PHPacketHeader ack; - ack.destination_id = p->header.source_id; - ack.type = PACKET_TYPE_ACK; - ack.rx_seq = p->header.tx_seq; - ack.data_size = 0; - - // Send the packet. - return PHLTransmitPacket(data, (PHPacketHandle)&ack); -} - -/** - * Send an NAck packet. - * \param[in] data The packet handler instance data pointer. - * \param[in] p A pointer to the packet buffer of the packet to be ACKed. - * \return 1 Success - * \return 0 Failure - */ -static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p) -{ - - // Create the NAck message - PHPacketHeader ack; - ack.destination_id = p->header.source_id; - ack.type = PACKET_TYPE_NACK; - ack.rx_seq = p->header.tx_seq; - ack.data_size = 0; - - // Set the packet. - return PHLTransmitPacket(data, (PHPacketHandle)&ack); -} diff --git a/flight/Modules/Radio/radio.c b/flight/Modules/Radio/radio.c index 8820e4081..7578f2ff8 100644 --- a/flight/Modules/Radio/radio.c +++ b/flight/Modules/Radio/radio.c @@ -83,7 +83,6 @@ typedef struct { // Error statistics. uint32_t radioTxErrors; uint32_t radioRxErrors; - uint32_t packetErrors; uint16_t txBytes; uint16_t rxBytes; @@ -262,7 +261,6 @@ static int32_t RadioInitialize(void) // Initialize the statistics. data->radioTxErrors = 0; data->radioRxErrors = 0; - data->packetErrors = 0; data->droppedPackets = 0; data->comTxRetries = 0; data->UAVTalkErrors = 0; @@ -315,12 +313,7 @@ static void radioReceiveTask(void *parameters) if(rx_bytes == 0) continue; data->rxBytes += rx_bytes; - - // Verify that the packet is valid and pass it on. - bool rx_error = PHVerifyPacket(pios_packet_handler, p, rx_bytes) < 0; - if(rx_error) - data->packetErrors++; - PHReceivePacket(pios_packet_handler, p, rx_error); + PHReceivePacket(pios_packet_handler, p); p = NULL; } } @@ -416,7 +409,7 @@ static void radioStatusTask(void *parameters) // Update the status pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); pipxStatus.Retries = data->comTxRetries; - pipxStatus.Errors = data->packetErrors; + pipxStatus.LinkQuality = PIOS_RFM22B_LinkQuality(pios_rfm22b_id); pipxStatus.UAVTalkErrors = data->UAVTalkErrors; pipxStatus.Dropped = data->droppedPackets; pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id); @@ -425,7 +418,7 @@ static void radioStatusTask(void *parameters) pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS); data->rxBytes = 0; pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED; - pipxStatus.RSSI = data->RSSI; + pipxStatus.RSSI = PIOS_RFM22B_LinkQuality(pios_rfm22b_id); LINK_LED_OFF; // Update the potential pairing contacts @@ -450,7 +443,6 @@ static void radioStatusTask(void *parameters) if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127)) { pipxStatus.Retries += data->pairStats[i].retries; - pipxStatus.Errors += data->pairStats[i].errors; pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors; pipxStatus.Dropped += data->pairStats[i].dropped; pipxStatus.Resets += data->pairStats[i].resets; diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 188f5f974..845794719 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -548,7 +548,7 @@ static void UAVTalkSendTask(void *parameters) else if(ev.event == EV_PACKET_RECEIVED) { // Receive the packet. - PHReceivePacket(pios_packet_handler, (PHPacketHandle)ev.obj, false); + PHReceivePacket(pios_packet_handler, (PHPacketHandle)ev.obj); } else if(ev.event == EV_TRANSMIT_PACKET) { diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index bd3925f03..d2c3ee72c 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -71,7 +71,7 @@ #define RADIOSTATS_UPDATE_PERIOD_MS 250 // this is too adjust the RF module so that it is on frequency -#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default +#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default #define OSC_LOAD_CAP_1 0x7D // board 1 #define OSC_LOAD_CAP_2 0x7B // board 2 #define OSC_LOAD_CAP_3 0x7E // board 3 @@ -206,10 +206,26 @@ struct pios_rfm22b_dev { // ezmac status register uint8_t ezmac_status; + // The packet transmission counts + uint32_t tx_packet_count; + uint32_t rx_packet_count; + + // The dropped packet counters + uint8_t slow_block; + uint8_t fast_block; + uint8_t slow_good_packets; + uint8_t fast_good_packets; + uint8_t slow_corrected_packets; + uint8_t fast_corrected_packets; + uint8_t slow_error_packets; + uint8_t fast_error_packets; + uint8_t slow_link_quality; + uint8_t fast_link_quality; + // Stats uint16_t resets; - uint32_t errors; - uint32_t irqs_processed; + uint16_t timeouts; + uint16_t errors; // the current RSSI (register value) uint8_t rssi; // RSSI in dBm @@ -557,10 +573,24 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu rfm22b_dev->int_status2 = 0; rfm22b_dev->ezmac_status = 0; + // Initlize the link stats. + rfm22b_dev->slow_block = 0; + rfm22b_dev->fast_block = 0; + rfm22b_dev->slow_good_packets = 0; + rfm22b_dev->fast_good_packets = 0; + rfm22b_dev->slow_corrected_packets = 0; + rfm22b_dev->fast_corrected_packets = 0; + rfm22b_dev->slow_error_packets = 0; + rfm22b_dev->fast_error_packets = 0; + rfm22b_dev->slow_link_quality = 255; + rfm22b_dev->fast_link_quality = 255; + // Initialize the stats. rfm22b_dev->resets = 0; + rfm22b_dev->timeouts = 0; rfm22b_dev->errors = 0; - rfm22b_dev->irqs_processed = 0; + rfm22b_dev->tx_packet_count = 0; + rfm22b_dev->rx_packet_count = 0; rfm22b_dev->rssi = 0; rfm22b_dev->rssi_dBm = -127; @@ -696,13 +726,38 @@ void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id) rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id; } -int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) +uint16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; - + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return 0; return rfm22b_dev->resets; } +uint16_t PIOS_RFM22B_Timeouts(uint32_t rfm22b_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return 0; + return rfm22b_dev->timeouts; +} + +uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return 0; + return rfm22b_dev->slow_link_quality; +} + +uint8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + if(!PIOS_RFM22B_validate(rfm22b_dev)) + return 0; + return rfm22b_dev->rssi_dBm; +} + static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail) { struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; @@ -741,11 +796,11 @@ bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_ /** * Receive a packet from the radio. * \param[in] rfm22b_id The rfm22b device. - * \param[in] p A pointer to the packet handle. + * \param[in] pret A pointer to the packet handle. * \param[in] max_delay The maximum time to delay waiting for a packet. * \return The number of bytes received. */ -uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay) +uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *pret, uint32_t max_delay) { struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; if (!PIOS_RFM22B_validate(rfm22b_dev)) @@ -763,9 +818,60 @@ uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint3 uint32_t rx_len = 0; if (rfm22b_dev->rx_packet_prev) { - *p = rfm22b_dev->rx_packet_prev; + PHPacketHandle p = rfm22b_dev->rx_packet_prev; + uint16_t len = PHPacketSizeECC(p); + + // Attempt to correct any errors in the packet. + decode_data((unsigned char*)p, len); + + // Check if there were any errors + bool rx_error = check_syndrome() != 0; + if(rx_error) + { + + // We have an error. Try to correct it. + if (correct_errors_erasures((unsigned char*)p, len, 0, 0) == 0) + { + // We couldn't correct the error, so drop the packet. + rfm22b_dev->fast_error_packets++; + PHReleaseRXPacket(pios_packet_handler, p); + } + else + { + // We corrected the error. + rfm22b_dev->fast_corrected_packets++; + rx_error = false; + } + + } + + // Return the packet if there were not uncorrectable errors. + if (!rx_error) + { + rfm22b_dev->fast_good_packets++; + *pret = p; + rx_len = rfm22b_dev->rx_packet_len; + + // Update the link statistics if necessary. + uint8_t fast_block = (p->header.seq_num >> 2) & 0xff; + uint8_t slow_block = (p->header.seq_num >> 4) & 0xff; + if (rfm22b_dev->fast_block != fast_block) + { + rfm22b_dev->fast_link_quality = (uint8_t)(((4 + (uint16_t)rfm22b_dev->fast_good_packets - rfm22b_dev->fast_error_packets) << 5) - 1); + rfm22b_dev->slow_good_packets += rfm22b_dev->fast_good_packets; + rfm22b_dev->slow_corrected_packets += rfm22b_dev->fast_corrected_packets; + rfm22b_dev->slow_error_packets += rfm22b_dev->fast_error_packets; + rfm22b_dev->fast_good_packets = rfm22b_dev->fast_corrected_packets = rfm22b_dev->fast_error_packets = 0; + rfm22b_dev->fast_block = fast_block; + } + if (rfm22b_dev->slow_block != slow_block) + { + rfm22b_dev->slow_link_quality = (uint8_t)(((16 + (uint16_t)rfm22b_dev->slow_good_packets - rfm22b_dev->slow_error_packets) << 3) - 1); + rfm22b_dev->slow_good_packets = rfm22b_dev->slow_corrected_packets = rfm22b_dev->slow_error_packets = 0; + rfm22b_dev->slow_block = slow_block; + } + } rfm22b_dev->rx_packet_prev = NULL; - rx_len = rfm22b_dev->rx_packet_len; } return rx_len; @@ -791,7 +897,6 @@ static void PIOS_RFM22B_Task(void *parameters) // Wait for a signal indicating an external interrupt or a pending send/receive request. if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) { - rfm22b_dev->irqs_processed++; lastEventTicks = xTaskGetTickCount(); // Process events through the state machine. @@ -1246,6 +1351,12 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev) rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0; return RFM22B_EVENT_RX_MODE; } + + // Add the error correcting code. + p->header.source_id = rfm22b_dev->deviceID; + p->header.seq_num = rfm22b_dev->tx_packet_count++; + encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p); + rfm22b_dev->tx_packet = p; rfm22b_dev->packet_start_ticks = xTaskGetTickCount(); if (rfm22b_dev->packet_start_ticks == 0) @@ -1317,20 +1428,14 @@ static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev) PHPacketHandle sph = (PHPacketHandle)&(rfm22b_dev->status_packet); // Queue the status message - rfm22b_dev->status_packet.header.source_id = rfm22b_dev->deviceID; rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast rfm22b_dev->status_packet.header.type = PACKET_TYPE_STATUS; rfm22b_dev->status_packet.header.data_size = PH_STATUS_DATA_SIZE(&(rfm22b_dev->status_packet)); - rfm22b_dev->status_packet.header.tx_seq = 0; - rfm22b_dev->status_packet.header.rx_seq = 0; rfm22b_dev->status_packet.errors = rfm22b_dev->errors; rfm22b_dev->status_packet.resets = rfm22b_dev->resets; rfm22b_dev->status_packet.retries = 0; rfm22b_dev->status_packet.uavtalk_errors = 0; rfm22b_dev->status_packet.dropped = 0; - - // Add the error correcting code. - encode_data((unsigned char*)sph, PHPacketSize(sph), (unsigned char*)sph); if (xQueueSend(rfm22b_dev->packetQueue, &sph, 0) != pdTRUE) return false; diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 65c823283..2d882dcb5 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -83,7 +83,10 @@ extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_p extern void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening); extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); -extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); +extern uint16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); +extern uint16_t PIOS_RFM22B_Timeouts(uint32_t rfm22b_id); +extern uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id); +extern uint8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay); extern uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay); diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp index f4e41f9ef..d6bd1b3fe 100644 --- a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp @@ -52,7 +52,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget } else { qDebug() << "Error: Object is unknown (PipXSettings)."; } - autoLoadWidgets(); + autoLoadWidgets(); addApplySaveButtons(m_pipx->Apply, m_pipx->Save); addUAVObjectToWidgetRelation("PipXSettings", "TelemetryConfig", m_pipx->TelemPortConfig); @@ -75,7 +75,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget addUAVObjectToWidgetRelation("PipXStatus", "RSSI", m_pipx->RSSI); addUAVObjectToWidgetRelation("PipXStatus", "AFC", m_pipx->RxAFC); addUAVObjectToWidgetRelation("PipXStatus", "Retries", m_pipx->Retries); - addUAVObjectToWidgetRelation("PipXStatus", "Errors", m_pipx->Errors); + addUAVObjectToWidgetRelation("PipXStatus", "LinkQuality", m_pipx->LinkQuality); addUAVObjectToWidgetRelation("PipXStatus", "UAVTalkErrors", m_pipx->UAVTalkErrors); addUAVObjectToWidgetRelation("PipXStatus", "Resets", m_pipx->Resets); addUAVObjectToWidgetRelation("PipXStatus", "Dropped", m_pipx->Dropped); diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index a3196692c..6abe1a830 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -1051,9 +1051,9 @@
- + - Errors + Link Quality Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -1061,7 +1061,7 @@ - + 101 diff --git a/shared/uavobjectdefinition/pipxstatus.xml b/shared/uavobjectdefinition/pipxstatus.xml index 3af8714c8..bbdc656c8 100755 --- a/shared/uavobjectdefinition/pipxstatus.xml +++ b/shared/uavobjectdefinition/pipxstatus.xml @@ -10,15 +10,14 @@ - - + From 9ea572f4f7787e8d4f6b354d805ed0f0ebb4897e Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Thu, 4 Oct 2012 21:23:44 -0700 Subject: [PATCH 499/508] RFM22B: Fixed the signedness of the return value of the RSSI function. --- flight/PiOS/Common/pios_rfm22b.c | 2 +- flight/PiOS/inc/pios_rfm22b.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index d2c3ee72c..476a56071 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -750,7 +750,7 @@ uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id) return rfm22b_dev->slow_link_quality; } -uint8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) +int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id) { struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; if(!PIOS_RFM22B_validate(rfm22b_dev)) diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 2d882dcb5..901d86788 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -86,7 +86,7 @@ extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern uint16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id); extern uint16_t PIOS_RFM22B_Timeouts(uint32_t rfm22b_id); extern uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id); -extern uint8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); +extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id); extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay); extern uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay); From 4284701b354a76920b2e98e382e2f03716fdf8d6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 5 Oct 2012 08:48:12 -0500 Subject: [PATCH 500/508] Update android objects --- .../uavtalk/uavobjects/FirmwareIAPObj.java | 62 ++++++++++++++++++- .../uavtalk/uavobjects/PipXSettings.java | 2 +- .../uavtalk/uavobjects/PipXStatus.java | 17 ++--- .../uavtalk/uavobjects/RelayTuning.java | 2 +- .../uavtalk/uavobjects/TaskInfo.java | 6 +- 5 files changed, 72 insertions(+), 17 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 90a9e8893..ed79ad0b4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -104,6 +104,66 @@ public class FirmwareIAPObj extends UAVDataObject { DescriptionElemNames.add("37"); DescriptionElemNames.add("38"); DescriptionElemNames.add("39"); + DescriptionElemNames.add("40"); + DescriptionElemNames.add("41"); + DescriptionElemNames.add("42"); + DescriptionElemNames.add("43"); + DescriptionElemNames.add("44"); + DescriptionElemNames.add("45"); + DescriptionElemNames.add("46"); + DescriptionElemNames.add("47"); + DescriptionElemNames.add("48"); + DescriptionElemNames.add("49"); + DescriptionElemNames.add("50"); + DescriptionElemNames.add("51"); + DescriptionElemNames.add("52"); + DescriptionElemNames.add("53"); + DescriptionElemNames.add("54"); + DescriptionElemNames.add("55"); + DescriptionElemNames.add("56"); + DescriptionElemNames.add("57"); + DescriptionElemNames.add("58"); + DescriptionElemNames.add("59"); + DescriptionElemNames.add("60"); + DescriptionElemNames.add("61"); + DescriptionElemNames.add("62"); + DescriptionElemNames.add("63"); + DescriptionElemNames.add("64"); + DescriptionElemNames.add("65"); + DescriptionElemNames.add("66"); + DescriptionElemNames.add("67"); + DescriptionElemNames.add("68"); + DescriptionElemNames.add("69"); + DescriptionElemNames.add("70"); + DescriptionElemNames.add("71"); + DescriptionElemNames.add("72"); + DescriptionElemNames.add("73"); + DescriptionElemNames.add("74"); + DescriptionElemNames.add("75"); + DescriptionElemNames.add("76"); + DescriptionElemNames.add("77"); + DescriptionElemNames.add("78"); + DescriptionElemNames.add("79"); + DescriptionElemNames.add("80"); + DescriptionElemNames.add("81"); + DescriptionElemNames.add("82"); + DescriptionElemNames.add("83"); + DescriptionElemNames.add("84"); + DescriptionElemNames.add("85"); + DescriptionElemNames.add("86"); + DescriptionElemNames.add("87"); + DescriptionElemNames.add("88"); + DescriptionElemNames.add("89"); + DescriptionElemNames.add("90"); + DescriptionElemNames.add("91"); + DescriptionElemNames.add("92"); + DescriptionElemNames.add("93"); + DescriptionElemNames.add("94"); + DescriptionElemNames.add("95"); + DescriptionElemNames.add("96"); + DescriptionElemNames.add("97"); + DescriptionElemNames.add("98"); + DescriptionElemNames.add("99"); fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); List CPUSerialElemNames = new ArrayList(); @@ -201,7 +261,7 @@ public class FirmwareIAPObj extends UAVDataObject { } // Constants - protected static final long OBJID = 0x3CCDFB68l; + protected static final long OBJID = 0x5E6E8FDCl; protected static final String NAME = "FirmwareIAPObj"; protected static String DESCRIPTION = "Queries board for SN, model, revision, and sends reset command"; protected static final boolean ISSINGLEINST = 1 > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java index 46cd3a998..70983914e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java @@ -252,7 +252,7 @@ public class PipXSettings extends UAVDataObject { getField("VCPConfig").setValue("Disabled"); getField("VCPSpeed").setValue("57600"); getField("RFSpeed").setValue("115200"); - getField("MaxRFPower").setValue("100"); + getField("MaxRFPower").setValue("1.25"); getField("MinPacketSize").setValue(50); getField("FrequencyCalibration").setValue(127); getField("AESKey").setValue(0,0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java index 5d08551e0..52f143ed6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java @@ -67,10 +67,6 @@ public class PipXStatus extends UAVDataObject { DeviceIDElemNames.add("0"); fields.add( new UAVObjectField("DeviceID", "", UAVObjectField.FieldType.UINT32, DeviceIDElemNames, null) ); - List AFCElemNames = new ArrayList(); - AFCElemNames.add("0"); - fields.add( new UAVObjectField("AFC", "", UAVObjectField.FieldType.INT32, AFCElemNames, null) ); - List PairIDsElemNames = new ArrayList(); PairIDsElemNames.add("0"); PairIDsElemNames.add("1"); @@ -86,10 +82,6 @@ public class PipXStatus extends UAVDataObject { RetriesElemNames.add("0"); fields.add( new UAVObjectField("Retries", "", UAVObjectField.FieldType.UINT16, RetriesElemNames, null) ); - List ErrorsElemNames = new ArrayList(); - ErrorsElemNames.add("0"); - fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT16, ErrorsElemNames, null) ); - List UAVTalkErrorsElemNames = new ArrayList(); UAVTalkErrorsElemNames.add("0"); fields.add( new UAVObjectField("UAVTalkErrors", "", UAVObjectField.FieldType.UINT16, UAVTalkErrorsElemNames, null) ); @@ -180,6 +172,10 @@ public class PipXStatus extends UAVDataObject { RSSIElemNames.add("0"); fields.add( new UAVObjectField("RSSI", "dBm", UAVObjectField.FieldType.INT8, RSSIElemNames, null) ); + List LinkQualityElemNames = new ArrayList(); + LinkQualityElemNames.add("0"); + fields.add( new UAVObjectField("LinkQuality", "", UAVObjectField.FieldType.UINT8, LinkQualityElemNames, null) ); + List LinkStateElemNames = new ArrayList(); LinkStateElemNames.add("0"); List LinkStateEnumOptions = new ArrayList(); @@ -243,13 +239,11 @@ public class PipXStatus extends UAVDataObject { getField("MaxFrequency").setValue(0); getField("FrequencyStepSize").setValue(0); getField("DeviceID").setValue(0); - getField("AFC").setValue(0); getField("PairIDs").setValue(0,0); getField("PairIDs").setValue(0,1); getField("PairIDs").setValue(0,2); getField("PairIDs").setValue(0,3); getField("Retries").setValue(0); - getField("Errors").setValue(0); getField("UAVTalkErrors").setValue(0); getField("Dropped").setValue(0); getField("Resets").setValue(0); @@ -257,6 +251,7 @@ public class PipXStatus extends UAVDataObject { getField("RXRate").setValue(0); getField("FrequencyBand").setValue(0); getField("RSSI").setValue(0); + getField("LinkQuality").setValue(0); getField("LinkState").setValue("Disconnected"); getField("PairSignalStrengths").setValue(-127,0); getField("PairSignalStrengths").setValue(-127,1); @@ -290,7 +285,7 @@ public class PipXStatus extends UAVDataObject { } // Constants - protected static final long OBJID = 0x3FC68A86l; + protected static final long OBJID = 0x85D29F8Al; protected static final String NAME = "PipXStatus"; protected static String DESCRIPTION = "PipXtreme device status."; protected static final boolean ISSINGLEINST = 1 > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java index 741e024a7..136785bee 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java @@ -88,7 +88,7 @@ public class RelayTuning extends UAVDataObject { UAVObject.Metadata metadata = new UAVObject.Metadata(); metadata.flags = UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 93136c414..c101adb77 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -74,8 +74,8 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("ModemRx"); StackRemainingElemNames.add("ModemTx"); StackRemainingElemNames.add("ModemStat"); - StackRemainingElemNames.add("EventDispatcher"); StackRemainingElemNames.add("Autotune"); + StackRemainingElemNames.add("EventDispatcher"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); @@ -101,8 +101,8 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("ModemRx"); RunningElemNames.add("ModemTx"); RunningElemNames.add("ModemStat"); - RunningElemNames.add("EventDispatcher"); RunningElemNames.add("Autotune"); + RunningElemNames.add("EventDispatcher"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); @@ -131,8 +131,8 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("ModemRx"); RunningTimeElemNames.add("ModemTx"); RunningTimeElemNames.add("ModemStat"); - RunningTimeElemNames.add("EventDispatcher"); RunningTimeElemNames.add("Autotune"); + RunningTimeElemNames.add("EventDispatcher"); fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); From 8a2f6f7398ed0da83654c871d964fb64bcec99f0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 5 Oct 2012 11:43:22 -0500 Subject: [PATCH 501/508] Package revomini --- package/Makefile | 2 +- package/osx/package | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/package/Makefile b/package/Makefile index 713ac0416..4133939d8 100644 --- a/package/Makefile +++ b/package/Makefile @@ -30,7 +30,7 @@ CLEAN_FLIGHT := YES endif # Set up targets -ALL_BOARDS := coptercontrol pipxtreme revolution +ALL_BOARDS := coptercontrol pipxtreme revolution revomini FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS)) FW_TARGETS_TOOLS := $(addprefix fw_, $(ALL_BOARDS)) BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS)) diff --git a/package/osx/package b/package/osx/package index 597bbc42c..871408c69 100755 --- a/package/osx/package +++ b/package/osx/package @@ -22,6 +22,7 @@ device=$(hdiutil attach "${TEMP_FILE}" | \ cp -r "${APP_PATH}" "/Volumes/${VOL_NAME}" #cp -r "${FW_DIR}" "/Volumes/${VOL_NAME}/firmware" cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" +cp "${FW_DIR}/fw_revomini-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_pipxtreme-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_revolution-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware" From 4b35cdf0ef769c2e274ed4739bddc1164e019b24 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 7 Oct 2012 09:42:20 -0500 Subject: [PATCH 502/508] OSX Simulation: Start populating the board and fw information This will allow testing the tablet to know what type of UAVOs to expect. --- flight/PiOS.osx/inc/pios_bl_helper.h | 46 +++ flight/PiOS.osx/inc/pios_board.h | 5 + flight/PiOS.osx/inc/pios_board_info.h | 24 ++ flight/PiOS.osx/inc/pios_iap.h | 45 +++ flight/PiOS.osx/inc/pios_sys.h | 85 +++--- flight/PiOS.osx/osx/pios_bl_helper.c | 53 ++++ flight/PiOS.osx/osx/pios_board_info.c | 20 ++ flight/PiOS.osx/osx/pios_iap.c | 69 +++++ flight/PiOS.osx/osx/pios_sys.c | 276 +++++++----------- flight/PiOS.osx/pios.h | 7 + flight/Revolution/Makefile.osx | 35 ++- .../Revolution/System/inc/pios_config_sim.h | 2 + 12 files changed, 452 insertions(+), 215 deletions(-) create mode 100644 flight/PiOS.osx/inc/pios_bl_helper.h create mode 100644 flight/PiOS.osx/inc/pios_board.h create mode 100644 flight/PiOS.osx/inc/pios_board_info.h create mode 100644 flight/PiOS.osx/inc/pios_iap.h create mode 100644 flight/PiOS.osx/osx/pios_bl_helper.c create mode 100644 flight/PiOS.osx/osx/pios_board_info.c create mode 100644 flight/PiOS.osx/osx/pios_iap.c diff --git a/flight/PiOS.osx/inc/pios_bl_helper.h b/flight/PiOS.osx/inc/pios_bl_helper.h new file mode 100644 index 000000000..e2e9e694e --- /dev/null +++ b/flight/PiOS.osx/inc/pios_bl_helper.h @@ -0,0 +1,46 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_BOOTLOADER Functions + * @brief HAL code to interface to the OpenPilot AHRS module + * @{ + * + * @file pios_bl_helper.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Bootloader Helper Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_BL_HELPER_H_ +#define PIOS_BL_HELPER_H_ + +extern uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress); + +extern uint8_t PIOS_BL_HELPER_FLASH_Ini(); + +extern uint32_t PIOS_BL_HELPER_CRC_Memory_Calc(); + +extern void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size); + +extern uint8_t PIOS_BL_HELPER_FLASH_Start(); + +extern void PIOS_BL_HELPER_CRC_Ini(); + +#endif /* PIOS_BL_HELPER_H_ */ diff --git a/flight/PiOS.osx/inc/pios_board.h b/flight/PiOS.osx/inc/pios_board.h new file mode 100644 index 000000000..463227910 --- /dev/null +++ b/flight/PiOS.osx/inc/pios_board.h @@ -0,0 +1,5 @@ +#ifndef PIOS_BOARD_H_ +#define PIOS_BOARD_H_ + + +#endif /* PIOS_BOARD_H_ */ diff --git a/flight/PiOS.osx/inc/pios_board_info.h b/flight/PiOS.osx/inc/pios_board_info.h new file mode 100644 index 000000000..3ff7aa886 --- /dev/null +++ b/flight/PiOS.osx/inc/pios_board_info.h @@ -0,0 +1,24 @@ +#ifndef PIOS_BOARD_INFO_H +#define PIOS_BOARD_INFO_H + +#include /* uint* */ + +#define PIOS_BOARD_INFO_BLOB_MAGIC 0xBDBDBDBD + +struct pios_board_info { + uint32_t magic; + uint8_t board_type; + uint8_t board_rev; + uint8_t bl_rev; + uint8_t hw_type; + uint32_t fw_base; + uint32_t fw_size; + uint32_t desc_base; + uint32_t desc_size; + uint32_t ee_base; + uint32_t ee_size; +} __attribute__((packed)); + +extern const struct pios_board_info pios_board_info_blob; + +#endif /* PIOS_BOARD_INFO_H */ diff --git a/flight/PiOS.osx/inc/pios_iap.h b/flight/PiOS.osx/inc/pios_iap.h new file mode 100644 index 000000000..d9b41170b --- /dev/null +++ b/flight/PiOS.osx/inc/pios_iap.h @@ -0,0 +1,45 @@ +/*! + * @File iap.h + * @Brief Header file for the In-Application-Programming Module + * + * Created on: Sep 6, 2010 + * Author: joe + */ + +#ifndef PIOS_IAP_H_ +#define PIOS_IAP_H_ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ + +/***************************************************************************************** + * Public Definitions/Macros + ****************************************************************************************/ +#if defined(STM32F4XX) +#define MAGIC_REG_1 RTC_BKP_DR1 +#define MAGIC_REG_2 RTC_BKP_DR2 +#define IAP_BOOTCOUNT RTC_BKP_DR3 +#else +#define MAGIC_REG_1 BKP_DR1 +#define MAGIC_REG_2 BKP_DR2 +#define IAP_BOOTCOUNT BKP_DR3 +#endif + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ +void PIOS_IAP_Init(void); +uint32_t PIOS_IAP_CheckRequest( void ); +void PIOS_IAP_SetRequest1(void); +void PIOS_IAP_SetRequest2(void); +void PIOS_IAP_ClearRequest(void); +uint16_t PIOS_IAP_ReadBootCount(void); +void PIOS_IAP_WriteBootCount(uint16_t); + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +#endif /* PIOS_IAP_H_ */ diff --git a/flight/PiOS.osx/inc/pios_sys.h b/flight/PiOS.osx/inc/pios_sys.h index 4e71b54a0..7f183a892 100644 --- a/flight/PiOS.osx/inc/pios_sys.h +++ b/flight/PiOS.osx/inc/pios_sys.h @@ -1,35 +1,50 @@ -/** - ****************************************************************************** - * - * @file pios_sys.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SYS_H -#define PIOS_SYS_H - -/* Public Functions */ -extern void PIOS_SYS_Init(void); -extern int32_t PIOS_SYS_Reset(void); -extern int32_t PIOS_SYS_SerialNumberGet(char *str); - -#endif /* PIOS_SYS_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SYS System Functions + * @brief PIOS System Initialization code + * @{ + * + * @file pios_sys.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief System and hardware Init functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SYS_H +#define PIOS_SYS_H + +#define PIOS_SYS_SERIAL_NUM_BINARY_LEN 12 +#define PIOS_SYS_SERIAL_NUM_ASCII_LEN (PIOS_SYS_SERIAL_NUM_BINARY_LEN * 2) + +/* Public Functions */ +extern void PIOS_SYS_Init(void); +extern int32_t PIOS_SYS_Reset(void); +extern uint32_t PIOS_SYS_getCPUFlashSize(void); +extern int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t array[PIOS_SYS_SERIAL_NUM_BINARY_LEN]); +extern int32_t PIOS_SYS_SerialNumberGet(char str[PIOS_SYS_SERIAL_NUM_ASCII_LEN+1]); + +#endif /* PIOS_SYS_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS.osx/osx/pios_bl_helper.c b/flight/PiOS.osx/osx/pios_bl_helper.c new file mode 100644 index 000000000..a7920e5d2 --- /dev/null +++ b/flight/PiOS.osx/osx/pios_bl_helper.c @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_BOOTLOADER Functions + * @brief HAL code to interface to the OpenPilot AHRS module + * @{ + * + * @file pios_bl_helper.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Bootloader Helper Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#if defined(PIOS_INCLUDE_BL_HELPER) +#include + +uint32_t PIOS_BL_HELPER_CRC_Memory_Calc() +{ + return 0; +} + +extern const struct fw_version_info fw_version_blob; +void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size) +{ + uint8_t * desc = (uint8_t *) &fw_version_blob; + for (uint32_t i = 0; i < size; i++) { + array[i] = desc[i]; + } +} + +void PIOS_BL_HELPER_CRC_Ini() +{ +} +#endif diff --git a/flight/PiOS.osx/osx/pios_board_info.c b/flight/PiOS.osx/osx/pios_board_info.c new file mode 100644 index 000000000..c273a881d --- /dev/null +++ b/flight/PiOS.osx/osx/pios_board_info.c @@ -0,0 +1,20 @@ +#include +#include + +#include "pios_board_info.h" + +const struct pios_board_info pios_board_info_blob = { + .magic = PIOS_BOARD_INFO_BLOB_MAGIC, + .board_type = BOARD_TYPE, + .board_rev = BOARD_REVISION, + .bl_rev = BOOTLOADER_VERSION, + .hw_type = HW_TYPE, + .fw_base = FW_BANK_BASE, + .fw_size = FW_BANK_SIZE - FW_DESC_SIZE, + .desc_base = FW_BANK_BASE + FW_BANK_SIZE - FW_DESC_SIZE, + .desc_size = FW_DESC_SIZE, +#ifdef EE_BANK_BASE + .ee_base = EE_BANK_BASE, + .ee_size = EE_BANK_SIZE, +#endif +}; diff --git a/flight/PiOS.osx/osx/pios_iap.c b/flight/PiOS.osx/osx/pios_iap.c new file mode 100644 index 000000000..be5b19536 --- /dev/null +++ b/flight/PiOS.osx/osx/pios_iap.c @@ -0,0 +1,69 @@ +/*! + * @File iap.c + * @Brief + * + * Created on: Sep 6, 2010 + * Author: joe + */ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + + return false; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ +} + +void PIOS_IAP_SetRequest2(void) +{ +} + +void PIOS_IAP_ClearRequest(void) +{ +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return 0; +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ +} diff --git a/flight/PiOS.osx/osx/pios_sys.c b/flight/PiOS.osx/osx/pios_sys.c index 063a2ed6b..d2c15c7b5 100644 --- a/flight/PiOS.osx/osx/pios_sys.c +++ b/flight/PiOS.osx/osx/pios_sys.c @@ -1,165 +1,111 @@ -/** - ****************************************************************************** - * - * @file pios_sys.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SYS System Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SYS) - - -/* Private Function Prototypes */ -void NVIC_Configuration(void); -void SysTick_Handler(void); - -/* Local Macros */ -#define MEM8(addr) (*((volatile uint8_t *)(addr))) - -/** -* Initialises all system peripherals -*/ -void PIOS_SYS_Init(void) -{ - - /** - * stub - */ - printf("PIOS_SYS_Init\n"); - - /* Initialise Basic NVIC */ - NVIC_Configuration(); - -#if defined(PIOS_INCLUDE_LED) - /* Initialise LEDs */ - PIOS_LED_Init(); -#endif -} - -/** -* Shutdown PIOS and reset the microcontroller:
-*
    -*
  • Disable all RTOS tasks -*
  • Disable all interrupts -*
  • Turn off all board LEDs -*
  • Reset STM32 -*
-* \return < 0 if reset failed -*/ -int32_t PIOS_SYS_Reset(void) -{ - /** - * stub - */ - printf("PIOS_SYS_Reset\n"); - /* Disable all RTOS tasks */ -#if defined(PIOS_INCLUDE_FREERTOS) - /* port specific FreeRTOS function to disable tasks (nested) */ - portENTER_CRITICAL(); -#endif - - - while(1); - - /* We will never reach this point */ - return -1; -} - -/** -* Returns the serial number as a string -* param[out] str pointer to a string which can store at least 32 digits + zero terminator! -* (24 digits returned for STM32) -* return < 0 if feature not supported -*/ -int32_t PIOS_SYS_SerialNumberGet(char *str) -{ - int i; - - /* Stored in the so called "electronic signature" */ - for(i=0; i<24; ++i) { - //uint8_t b = MEM8(0x1ffff7e8 + (i/2)); - //if( !(i & 1) ) - //b >>= 4; - //b &= 0x0f; - - //str[i] = ((b > 9) ? ('A'-10) : '0') + b; - str[i]='6'; - } - str[i] = 0; - - /* No error */ - return 0; -} - -/** -* Configures Vector Table base location and SysTick -*/ -void NVIC_Configuration(void) -{ - /** - * stub - */ - printf("NVIC_Configuration\n"); - /* Set the Vector Table base address as specified in .ld file */ - //NVIC_SetVectorTable(PIOS_NVIC_VECTTAB_FLASH, 0x0); - - /* 4 bits for Interrupt priorities so no sub priorities */ - //NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); - - /* Configure HCLK clock as SysTick clock source. */ - //SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); -} - -#ifdef USE_FULL_ASSERT -/** -* Reports the name of the source file and the source line number -* where the assert_param error has occurred. -* \param[in] file pointer to the source file name -* \param[in] line assert_param error line source number -* \retval None -*/ -void assert_failed(uint8_t* file, uint32_t line) -{ - /* When serial debugging is implemented, use something like this. */ - /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ - printf("Wrong parameters value: file %s on line %d\r\n", file, line); - - /* Setup the LEDs to Alternate */ - PIOS_LED_On(LED1); - PIOS_LED_Off(LED2); - - /* Infinite loop */ - while (1) - { - PIOS_LED_Toggle(LED1); - PIOS_LED_Toggle(LED2); - for(int i = 0; i < 1000000; i++); - } -} -#endif - -#endif +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SYS System Functions + * @brief PIOS System Initialization code + * @{ + * + * @file pios_sys.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Sets up basic STM32 system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SYS) + + +/** +* Initialises all system peripherals +*/ +void PIOS_SYS_Init(void) +{ + +} + +/** +* Shutdown PIOS and reset the microcontroller:
+*
    +*
  • Disable all RTOS tasks +*
  • Disable all interrupts +*
  • Turn off all board LEDs +*
  • Reset STM32 +*
+* \return < 0 if reset failed +*/ +int32_t PIOS_SYS_Reset(void) +{ + /* We will never reach this point */ + return -1; +} + +/** +* Returns the CPU's flash size (in bytes) +*/ +uint32_t PIOS_SYS_getCPUFlashSize(void) +{ + return 1024000; +} + +/** +* Returns the serial number as a string +* param[out] uint8_t pointer to a string which can store at least 12 bytes +* (12 bytes returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) +{ + /* Stored in the so called "electronic signature" */ + for (int i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) { + array[i] = 0xff; + } + + /* No error */ + return 0; +} + +/** +* Returns the serial number as a string +* param[out] str pointer to a string which can store at least 32 digits + zero terminator! +* (24 digits returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGet(char *str) +{ + /* Stored in the so called "electronic signature" */ + int i; + for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) { + str[i] = 'F'; + } + str[i] = '\0'; + + /* No error */ + return 0; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS.osx/pios.h b/flight/PiOS.osx/pios.h index f02a2a05d..debdef9b7 100644 --- a/flight/PiOS.osx/pios.h +++ b/flight/PiOS.osx/pios.h @@ -72,6 +72,13 @@ #include #include +#if defined(PIOS_INCLUDE_IAP) +#include +#endif +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#endif + #define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) #endif /* PIOS_H */ diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index e57bf7969..95f1f906e 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -22,6 +22,11 @@ # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA ##### +BOARD_NAME=revolution +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +TOP := $(realpath $(WHEREAMI)/../../) +include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk + # Set developer code and compile options # Set to YES to compile for debugging @@ -53,6 +58,7 @@ USE_THUMB_MODE = YES MODULES += Actuator ManualControl Stabilization MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner MODULES += Attitude/revolution +MODULES += FirmwareIAP #MODULES += OveroSync/simulated # To run simulation instead of connect to SITL @@ -60,20 +66,17 @@ MODULES += Sensors/simulated MODULES += Telemetry -# MCU name, submodel and board -# - MCU used for compiler-option (-mtune) -# - MODEL used for linker-script name (-T) and passed as define -# - BOARD just passed as define (optional) -MCU = i686 -#CHIP = STM32F103RET -#BOARD = STM3210E_OP -MODEL = HD -ifeq ($(USE_BOOTLOADER), YES) -BOOT_MODEL = $(MODEL)_BL +BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) +BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) +BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) +BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) +BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) -else -BOOT_MODEL = $(MODEL)_NB -endif +# Since we are simulating all this firmware the code needs to know what the BL would +# normally contain +CFLAGS += $(BLONLY_CDEFS) # Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) OUTDIR = ../../build/sim_osx @@ -177,6 +180,9 @@ SRC += $(PIOSPOSIX)/pios_com.c SRC += $(PIOSPOSIX)/pios_servo.c SRC += $(PIOSPOSIX)/pios_wdg.c SRC += $(PIOSPOSIX)/pios_debug.c +SRC += $(PIOSPOSIX)/pios_bl_helper.c +SRC += $(PIOSPOSIX)/pios_iap.c +SRC += $(PIOSPOSIX)/pios_board_info.c SRC += $(PIOSPOSIX)/pios_rcvr.c SRC += $(PIOSPOSIX)/pios_gcsrcvr.c @@ -311,7 +317,7 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -g$(DEBUGF) -DDEBUG +CFLAGS += -g$(DEBUGF) -DDEBUG endif CFLAGS += -DDIAGNOSTICS @@ -320,7 +326,6 @@ CFLAGS += -DDIAG_TASKS CFLAGS += $(CFLAGS_UAVOBJECTS) CFLAGS += -DARCH_POSIX CFLAGS += -O$(OPT) -CFLAGS += -mtune=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. diff --git a/flight/Revolution/System/inc/pios_config_sim.h b/flight/Revolution/System/inc/pios_config_sim.h index e7f7aed82..15eb28321 100644 --- a/flight/Revolution/System/inc/pios_config_sim.h +++ b/flight/Revolution/System/inc/pios_config_sim.h @@ -44,6 +44,8 @@ #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_RCVR #define PIOS_INCLUDE_GCSRCVR +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_BL_HELPER #define PIOS_RCVR_MAX_CHANNELS 12 #define PIOS_RCVR_MAX_DEVS 3 From 72c84fc49ce56af3fd7af3af45d89984cbb5354e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 9 Oct 2012 09:48:02 -0500 Subject: [PATCH 503/508] Upgrade to FreeRTOS 7.2.0 --- .../FreeRTOS/Source/include/FreeRTOS.h | 995 ++-- .../FreeRTOS/Source/include/StackMacros.h | 349 +- .../FreeRTOS/Source/include/croutine.h | 1505 ++--- .../Libraries/FreeRTOS/Source/include/list.h | 645 ++- .../FreeRTOS/Source/include/mpu_wrappers.h | 281 +- .../FreeRTOS/Source/include/portable.h | 793 +-- .../FreeRTOS/Source/include/projdefs.h | 172 +- .../Libraries/FreeRTOS/Source/include/queue.h | 2564 ++++----- .../FreeRTOS/Source/include/semphr.h | 1511 ++--- .../Libraries/FreeRTOS/Source/include/task.h | 2625 +++++---- .../FreeRTOS/Source/include/timers.h | 1892 +++---- .../Common/Libraries/FreeRTOS/Source/list.c | 395 +- .../Common/Libraries/FreeRTOS/Source/queue.c | 3218 ++++++----- .../Common/Libraries/FreeRTOS/Source/tasks.c | 5001 ++++++++--------- .../Common/Libraries/FreeRTOS/Source/timers.c | 1359 ++--- .../FreeRTOS/Source/include/FreeRTOS.h | 94 +- .../FreeRTOS/Source/include/StackMacros.h | 35 +- .../FreeRTOS/Source/include/croutine.h | 35 +- .../Libraries/FreeRTOS/Source/include/list.h | 53 +- .../FreeRTOS/Source/include/mpu_wrappers.h | 39 +- .../FreeRTOS/Source/include/portable.h | 35 +- .../FreeRTOS/Source/include/projdefs.h | 40 +- .../Libraries/FreeRTOS/Source/include/queue.h | 74 +- .../FreeRTOS/Source/include/semphr.h | 118 +- .../Libraries/FreeRTOS/Source/include/task.h | 130 +- .../FreeRTOS/Source/include/timers.h | 66 +- .../Libraries/FreeRTOS/Source/list.c | 35 +- .../Source/portable/GCC/ARM_CM3/port.c | 41 +- .../Source/portable/GCC/ARM_CM3/portmacro.h | 40 +- .../Libraries/FreeRTOS/Source/queue.c | 261 +- .../Libraries/FreeRTOS/Source/tasks.c | 409 +- .../Libraries/FreeRTOS/Source/timers.c | 71 +- .../Source/portable/GCC/ARM_CM4/port.c | 364 -- .../Source/portable/GCC/ARM_CM4F/port.c | 350 ++ .../GCC/{ARM_CM4 => ARM_CM4F}/portmacro.h | 334 +- flight/PiOS/STM32F4xx/library.mk | 4 +- 36 files changed, 13330 insertions(+), 12603 deletions(-) mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c mode change 100644 => 100755 flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c mode change 100644 => 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c delete mode 100644 flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c create mode 100755 flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c rename flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/{ARM_CM4 => ARM_CM4F}/portmacro.h (72%) mode change 100644 => 100755 diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h old mode 100644 new mode 100755 index e495d7d35..c12f5d76f --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,473 +1,522 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_xTaskGetIdleTaskHandle - #define INCLUDE_xTaskGetIdleTaskHandle 0 -#endif - -#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle - #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 -#endif - -#ifndef INCLUDE_pcTaskGetTaskName - #define INCLUDE_pcTaskGetTaskName 0 -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_TIMERS - #define configUSE_TIMERS 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef configASSERT - #define configASSERT( x ) -#endif - -/* The timers module relies on xTaskGetSchedulerState(). */ -#if configUSE_TIMERS == 1 - - #ifndef configTIMER_TASK_PRIORITY - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. - #endif /* configTIMER_TASK_PRIORITY */ - - #ifndef configTIMER_QUEUE_LENGTH - #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. - #endif /* configTIMER_QUEUE_LENGTH */ - - #ifndef configTIMER_TASK_STACK_DEPTH - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. - #endif /* configTIMER_TASK_STACK_DEPTH */ - -#endif /* configUSE_TIMERS */ - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0U -#endif - -#if ( configQUEUE_REGISTRY_SIZE < 1 ) - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - -#ifndef portPOINTER_SIZE_TYPE - #define portPOINTER_SIZE_TYPE unsigned long -#endif - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED() -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED - #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED() -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef traceTIMER_CREATE - #define traceTIMER_CREATE( pxNewTimer ) -#endif - -#ifndef traceTIMER_CREATE_FAILED - #define traceTIMER_CREATE_FAILED() -#endif - -#ifndef traceTIMER_COMMAND_SEND - #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) -#endif - -#ifndef traceTIMER_EXPIRED - #define traceTIMER_EXPIRED( pxTimer ) -#endif - -#ifndef traceTIMER_COMMAND_RECEIVED - #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. - #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle + #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 +#endif + +#ifndef INCLUDE_xQueueGetMutexHolder + #define INCLUDE_xQueueGetMutexHolder 0 +#endif + +#ifndef INCLUDE_pcTaskGetTaskName + #define INCLUDE_pcTaskGetTaskName 0 +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef configASSERT + #define configASSERT( x ) +#endif + +#ifndef portALIGNMENT_ASSERT_pxCurrentTCB + #define portALIGNMENT_ASSERT_pxCurrentTCB configASSERT +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + +#ifndef portCLEAN_UP_TCB + #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef portSETUP_TCB + #define portSETUP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1 ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE unsigned long +#endif + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceTASK_PRIORITY_INHERIT + /* Called when a task attempts to take a mutex that is already held by a + lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task + that holds the mutex. uxInheritedPriority is the priority the mutex holder + will inherit (the priority of the task that is attempting to obtain the + muted. */ + #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) +#endif + +#ifndef traceTASK_PRIORITY_DISINHERIT + /* Called when a task releases a mutex, the holding of which had resulted in + the task inheriting the priority of a higher priority task. + pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the + mutex. uxOriginalPriority is the task's configured (base) priority. */ + #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceMOVED_TASK_TO_READY_STATE + #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED( ucQueueType ) +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h old mode 100644 new mode 100755 index 8b555cec7..daf3ce408 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,168 +1,181 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h old mode 100644 new mode 100755 index a5a0d6980..f2843cde2 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,746 +1,759 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include croutine.h" -#endif - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( ( xTicksToDelay ) > 0 ) \ - { \ - vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ - } \ - crSET_STATE0( ( xHandle ) ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ - } \ - if( *( pxResult ) == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *( pxResult ) = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h old mode 100644 new mode 100755 index d5dfda514..28d4f248e --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h @@ -1,308 +1,337 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) - -/* - * Access macro the retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro the retrieve the value of the list item at the head of a given - * list. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = ( pxList ); \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) + +/* + * Access macro to get the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_OWNER( pxListItem ) ( pxListItem )->pvOwner + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) + +/* + * Access macro to retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro the retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) + +/* + * This provides a crude means of knowing if a list has been initialised, as + * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() + * function. + */ +#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h old mode 100644 new mode 100755 index a2759d5e8..be49c3d88 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,135 +1,146 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskStartTrace MPU_vTaskStartTrace - #define ulTaskEndTrace MPU_ulTaskEndTrace - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueCreate MPU_xQueueCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueGenericCreate MPU_xQueueGenericCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h old mode 100644 new mode 100755 index b46ad87d3..88cfbb2b7 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h @@ -1,390 +1,403 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h old mode 100644 new mode 100755 index d0b73c85e..c69db9237 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,82 +1,90 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -void PIOS_DEBUG_PinValue8Bit(unsigned char value); - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -// Uncomment this line to output the second character of the task that is being switched in on the debug-pins -//#define traceTASK_SWITCHED_IN() PIOS_DEBUG_PinValue8Bit(pxCurrentTCB->pcTaskName[1]); - -#endif /* PROJDEFS_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h old mode 100644 new mode 100755 index 5026306bd..e48cf07a6 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h @@ -1,1264 +1,1300 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" -#endif - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - -/** - * Type by which queues are referenced. For example, a call to xQueueCreate - * returns (via a pointer parameter) an xQueueHandle variable that can then - * be used as a parameter to xQueueSend(), xQueueReceive(), etc. - */ -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle pxQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); - -/* - * Utilities to query queue that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting() instead of calling these functions directly. - */ -xQueueHandle xQueueCreateMutex( void ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0U - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - -/* Not a public API function, hence the 'Restricted' in the name. */ -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate + * returns (via a pointer parameter) an xQueueHandle variable that can then + * be used as a parameter to xQueueSend(), xQueueReceive(), etc. + */ +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* For internal use only. These definitions *must* match those in queue.c. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle pxQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ); + +/* + * Utilities to query queues that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex(), + * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling + * these functions directly. + */ +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); +void* xQueueGetMutexHolder( xQueueHandle xSemaphore ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); + +/* + * Reset a queue back to its original empty state. pdPASS is returned if the + * queue is successfully reset. pdFAIL is returned if the queue could not be + * reset because there are tasks blocked on the queue waiting to either + * receive from the queue or send to the queue. + */ +#define xQueueReset( pxQueue ) xQueueGenericReset( pxQueue, pdFALSE ) + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0U + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + +/* + * Generic version of the queue creation function, which is in turn called by + * any queue, semaphore or mutex creation function or macro. + */ +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ); + +/* Not public API functions. */ +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ); + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h old mode 100644 new mode 100755 index 13b8ee63d..65c77c7c9 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,724 +1,787 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" -#endif - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) { \ - ( xSemaphore ) = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ - if( ( xSemaphore ) != NULL ) \ - { \ - xSemaphoreGive( ( xSemaphore ) ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex() - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) - -/** - * semphr. h - *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
- * - * Delete a semaphore. This function must be used with care. For example, - * do not delete a mutex type semaphore if the mutex is held by a task. - * - * @param xSemaphore A handle to the semaphore to be deleted. - * - * \page vSemaphoreDelete vSemaphoreDelete - * \ingroup Semaphores - */ -#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) xSemaphore ) - -#endif /* SEMAPHORE_H */ - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include semphr.h" +#endif + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) \ + { \ + ( xSemaphore ) = xQueueGenericCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreTakeFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to take a semaphore from an ISR. The semaphore must have + * previously been created with a call to vSemaphoreCreateBinary() or + * xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR, however taking a semaphore from an ISR + * is not a common operation. It is likely to only be useful when taking a + * counting semaphore when an interrupt is obtaining an object from a resource + * pool (when the semaphore count indicates the number of resources available). + * + * @param xSemaphore A handle to the semaphore being taken. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully taken, otherwise + * pdFALSE + */ +#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) + +/** + * semphr. h + *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \page vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) ( xSemaphore ) ) + +/** + * semphr.h + *
xTaskHandle xSemaphoreGetMutexHolder( xSemaphoreHandle xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + * Note: This Is is a good way of determining if the calling task is the mutex + * holder, but not a good way of determining the identity of the mutex holder as + * the holder may change between the function exiting and the returned value + * being tested. + */ +#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h old mode 100644 new mode 100755 index 4e69f8c54..e7a989d40 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h @@ -1,1323 +1,1302 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef TASK_H -#define TASK_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include task.h" -#endif - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V7.0.1" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
portTickType xTaskGetTickCountFromISR( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * This is a version of xTaskGetTickCount() that is safe to be called from an - * ISR - provided that portTickType is the natural word size of the - * microcontroller being used or interrupt nesting is either not supported or - * not being used. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
- * - * @return The text (human readable) name of the task referenced by the handle - * xTaskToQueury. A task can query its own name by either passing in its own - * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be - * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. - * - * \page pcTaskGetTaskName pcTaskGetTaskName - * \ingroup TaskUtils - */ -signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
- * - * Starts a real time kernel activity trace. The trace logs the identity of - * which task is running when. - * - * The trace file is stored in binary format. A separate DOS utility called - * convtrce.exe is used to convert this into a tab delimited text file which - * can be viewed and plotted in a spread sheet. - * - * @param pcBuffer The buffer into which the trace will be written. - * - * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue - * until either the buffer in full, or ulTaskEndTrace () is called. - * - * \page vTaskStartTrace vTaskStartTrace - * \ingroup TaskUtils - */ -void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned long ulTaskEndTrace( void );
- * - * Stops a kernel activity trace. See vTaskStartTrace (). - * - * @return The number of bytes that have been written into the trace buffer. - * - * \page usTaskEndTrace usTaskEndTrace - * \ingroup TaskUtils - */ -unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in words, so on a 32 bit machine - * a value of 1 means 4 bytes) since the task started. The smaller the returned - * number the closer the task has come to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
- * - * Returns the run time of selected task - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The run time of selected task - */ -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); - -/* When using trace macros it is sometimes necessary to include tasks.h before -FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, -so the following two prototypes will cause a compilation error. This can be -fixed by simply guarding against the inclusion of these two prototypes unless -they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration -constant. */ -#ifdef configUSE_APPLICATION_TASK_TAG - #if configUSE_APPLICATION_TASK_TAG == 1 - /** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - - /** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ -#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - -/** - * xTaskGetIdleTaskHandle() is only available if - * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the idle task. It is not valid to call - * xTaskGetIdleTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTaskGetIdleTaskHandle( void ); - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * This function performs nearly the same function as vTaskPlaceOnEventList(). - * The difference being that this function does not permit tasks to block - * indefinitely, whereas vTaskPlaceOnEventList() does. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - Selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef TASK_H +#define TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V7.2.0" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
portTickType xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that portTickType is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQueury. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be + * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. + * + * \page pcTaskGetTaskName pcTaskGetTaskName + * \ingroup TaskUtils + */ +signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/* When using trace macros it is sometimes necessary to include tasks.h before +FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTaskGetIdleTaskHandle( void ); + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +/* + * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. + */ +unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ); + +/* + * Set the uxTCBNumber of the task referenced by the xTask parameter to + * ucHandle. + */ +void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ); + + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h old mode 100644 new mode 100755 index 606439e0d..5f62368f5 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h @@ -1,940 +1,952 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef TIMERS_H -#define TIMERS_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include timers.h" -#endif - -#include "portable.h" -#include "list.h" -#include "task.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* IDs for commands that can be sent/received on the timer queue. These are to -be used solely through the macros that make up the public software timer API, -as defined below. */ -#define tmrCOMMAND_START 0 -#define tmrCOMMAND_STOP 1 -#define tmrCOMMAND_CHANGE_PERIOD 2 -#define tmrCOMMAND_DELETE 3 - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - - /** - * Type by which software timers are referenced. For example, a call to - * xTimerCreate() returns an xTimerHandle variable that can then be used to - * reference the subject timer in calls to other software timer API functions - * (for example, xTimerStart(), xTimerReset(), etc.). - */ -typedef void * xTimerHandle; - -/* Define the prototype to which timer callback functions must conform. */ -typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); - -/** - * xTimerHandle xTimerCreate( const signed char *pcTimerName, - * portTickType xTimerPeriod, - * unsigned portBASE_TYPE uxAutoReload, - * void * pvTimerID, - * tmrTIMER_CALLBACK pxCallbackFunction ); - * - * Creates a new software timer instance. This allocates the storage required - * by the new timer, initialises the new timers internal state, and returns a - * handle by which the new timer can be referenced. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param pcTimerName A text name that is assigned to the timer. This is done - * purely to assist debugging. The kernel itself only ever references a timer by - * its handle, and never by its name. - * - * @param xTimerPeriod The timer period. The time is defined in tick periods so - * the constant portTICK_RATE_MS can be used to convert a time that has been - * specified in milliseconds. For example, if the timer must expire after 100 - * ticks, then xTimerPeriod should be set to 100. Alternatively, if the timer - * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) - * provided configTICK_RATE_HZ is less than or equal to 1000. - * - * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will - * expire repeatedly with a frequency set by the xTimerPeriod parameter. If - * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and - * enter the dormant state after it expires. - * - * @param pvTimerID An identifier that is assigned to the timer being created. - * Typically this would be used in the timer callback function to identify which - * timer expired when the same callback function is assigned to more than one - * timer. - * - * @param pxCallbackFunction The function to call when the timer expires. - * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, - * which is "void vCallbackFunction( xTimerHandle xTimer );". - * - * @return If the timer is successfully create then a handle to the newly - * created timer is returned. If the timer cannot be created (because either - * there is insufficient FreeRTOS heap remaining to allocate the timer - * structures, or the timer period was set to 0) then 0 is returned. - * - * Example usage: - * - * - * #define NUM_TIMERS 5 - * - * // An array to hold handles to the created timers. - * xTimerHandle xTimers[ NUM_TIMERS ]; - * - * // An array to hold a count of the number of times each timer expires. - * long lExpireCounters[ NUM_TIMERS ] = { 0 }; - * - * // Define a callback function that will be used by multiple timer instances. - * // The callback function does nothing but count the number of times the - * // associated timer expires, and stop the timer once the timer has expired - * // 10 times. - * void vTimerCallback( xTimerHandle pxTimer ) - * { - * long lArrayIndex; - * const long xMaxExpiryCountBeforeStopping = 10; - * - * // Optionally do something if the pxTimer parameter is NULL. - * configASSERT( pxTimer ); - * - * // Which timer expired? - * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); - * - * // Increment the number of times that pxTimer has expired. - * lExpireCounters[ lArrayIndex ] += 1; - * - * // If the timer has expired 10 times then stop it from running. - * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) - * { - * // Do not use a block time if calling a timer API function from a - * // timer callback function, as doing so could cause a deadlock! - * xTimerStop( pxTimer, 0 ); - * } - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start some timers. Starting the timers before the scheduler - * // has been started means the timers will start running immediately that - * // the scheduler starts. - * for( x = 0; x < NUM_TIMERS; x++ ) - * { - * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. - * ( 100 * x ), // The timer period in ticks. - * pdTRUE, // The timers will auto-reload themselves when they expire. - * ( void * ) x, // Assign each timer a unique id equal to its array index. - * vTimerCallback // Each timer calls the same callback when it expires. - * ); - * - * if( xTimers[ x ] == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timers running as they have already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; - -/** - * void *pvTimerGetTimerID( xTimerHandle xTimer ); - * - * Returns the ID assigned to the timer. - * - * IDs are assigned to timers using the pvTimerID parameter of the call to - * xTimerCreated() that was used to create the timer. - * - * If the same callback function is assigned to multiple timers then the timer - * ID can be used within the callback function to identify which timer actually - * expired. - * - * @param xTimer The timer being queried. - * - * @return The ID assigned to the timer being queried. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - */ -void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); - * - * Queries a timer to see if it is active or dormant. - * - * A timer will be dormant if: - * 1) It has been created but not started, or - * 2) It is an expired on-shot timer that has not been restarted. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param xTimer The timer being queried. - * - * @return pdFALSE will be returned if the timer is dormant. A value other than - * pdFALSE will be returned if the timer is active. - * - * Example usage: - * - * // This function assumes xTimer has already been created. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is active, do something. - * } - * else - * { - * // xTimer is not active, do something else. - * } - * } - */ -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * xTimerGetTimerDaemonTaskHandle() is only available if - * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the timer service/daemon task. It it not valid - * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); - -/** - * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStart() starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerStart() has equivalent functionality - * to the xTimerReset() API function. - * - * Starting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerStart() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerStart() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerStart() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() - * to be available. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the start command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStop() stops a timer that was previously started using either of the - * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), - * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. - * - * Stopping a timer ensures the timer is not in the active state. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() - * to be available. - * - * @param xTimer The handle of the timer being stopped. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the stop command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerChangePeriod() changes the period of a timer that was previously - * created using the xTimerCreate() API function. - * - * xTimerChangePeriod() can be called to change the period of an active or - * dormant state timer. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerChangePeriod() to be available. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the change period command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerChangePeriod() was called. xBlockTime is ignored if - * xTimerChangePeriod() is called before the scheduler is started. - * - * @return pdFAIL will be returned if the change period command could not be - * sent to the timer command queue even after xBlockTime ticks had passed. - * pdPASS will be returned if the command was successfully sent to the timer - * command queue. When the command is actually processed will depend on the - * priority of the timer service/daemon task relative to other tasks in the - * system. The timer service/daemon task priority is set by the - * configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This function assumes xTimer has already been created. If the timer - * // referenced by xTimer is already active when it is called, then the timer - * // is deleted. If the timer referenced by xTimer is not active when it is - * // called, then the period of the timer is set to 500ms and the timer is - * // started. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is already active - delete it. - * xTimerDelete( xTimer ); - * } - * else - * { - * // xTimer is not active, change its period to 500ms. This will also - * // cause the timer to start. Block for a maximum of 100 ticks if the - * // change period command cannot immediately be sent to the timer - * // command queue. - * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) - * { - * // The command was successfully sent. - * } - * else - * { - * // The command could not be sent, even after waiting for 100 ticks - * // to pass. Take appropriate action here. - * } - * } - * } - */ - #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerDelete() deletes a timer that was previously created using the - * xTimerCreate() API function. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerDelete() to be available. - * - * @param xTimer The handle of the timer being deleted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the delete command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() - * is called before the scheduler is started. - * - * @return pdFAIL will be returned if the delete command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerChangePeriod() API function example usage scenario. - */ -#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerReset() re-starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerReset() will cause the timer to - * re-evaluate its expiry time so that it is relative to when xTimerReset() was - * called. If the timer was in the dormant state then xTimerReset() has - * equivalent functionality to the xTimerStart() API function. - * - * Resetting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerReset() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerReset() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerReset() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() - * to be available. - * - * @param xTimer The handle of the timer being reset/started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the reset command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer. - * - * xTimerHandle xBacklightTimer = NULL; - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press event handler. - * void vKeyPressEventHandler( char cKey ) - * { - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. Wait 10 ticks for the command to be successfully sent - * // if it cannot be sent immediately. - * vSetBacklightState( BACKLIGHT_ON ); - * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start the one-shot timer that is responsible for turning - * // the back-light off if no keys are pressed within a 5 second period. - * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. - * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. - * pdFALSE, // The timer is a one-shot timer. - * 0, // The id is not used by the callback so can take any value. - * vBacklightTimerCallback // The callback function that switches the LCD back-light off. - * ); - * - * if( xBacklightTimer == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timer running as it has already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStart() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStartFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStartFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStartFromISR() function. If - * xTimerStartFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerStartFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then restart the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The start command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStop() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being stopped. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStopFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStopFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStopFromISR() function. If - * xTimerStopFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the timer should be simply stopped. - * - * // The interrupt service routine that stops the timer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - simply stop the timer. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The stop command was not executed successfully. Take appropriate - * // action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerChangePeriod() that can be called from an interrupt - * service routine. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerChangePeriodFromISR() writes a message to the - * timer command queue, so has the potential to transition the timer service/ - * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() - * causes the timer service/daemon task to leave the Blocked state, and the - * timer service/daemon task has a priority equal to or greater than the - * currently executing task (the task that was interrupted), then - * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the - * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets - * this value to pdTRUE then a context switch should be performed before the - * interrupt exits. - * - * @return pdFAIL will be returned if the command to change the timers period - * could not be sent to the timer command queue. pdPASS will be returned if the - * command was successfully sent to the timer command queue. When the command - * is actually processed will depend on the priority of the timer service/daemon - * task relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the period of xTimer should be changed to 500ms. - * - * // The interrupt service routine that changes the period of xTimer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - change the period of xTimer to 500ms. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The command to change the timers period was not executed - * // successfully. Take appropriate action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerReset() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer that is to be started, reset, or - * restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerResetFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerResetFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerResetFromISR() function. If - * xTimerResetFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerResetFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/* - * Functions beyond this part are not part of the public API and are intended - * for use by the kernel only. - */ -portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TIMERS_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +#include "portable.h" +#include "list.h" +#include "task.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. */ +#define tmrCOMMAND_START 0 +#define tmrCOMMAND_STOP 1 +#define tmrCOMMAND_CHANGE_PERIOD 2 +#define tmrCOMMAND_DELETE 3 + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + + /** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an xTimerHandle variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +typedef void * xTimerHandle; + +/* Define the prototype to which timer callback functions must conform. */ +typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); + +/** + * xTimerHandle xTimerCreate( const signed char *pcTimerName, + * portTickType xTimerPeriodInTicks, + * unsigned portBASE_TYPE uxAutoReload, + * void * pvTimerID, + * tmrTIMER_CALLBACK pxCallbackFunction ); + * + * Creates a new software timer instance. This allocates the storage required + * by the new timer, initialises the new timers internal state, and returns a + * handle by which the new timer can be referenced. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer by + * its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick periods so + * the constant portTICK_RATE_MS can be used to convert a time that has been + * specified in milliseconds. For example, if the timer must expire after 100 + * ticks, then xTimerPeriodInTicks should be set to 100. Alternatively, if the timer + * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) + * provided configTICK_RATE_HZ is less than or equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, + * which is "void vCallbackFunction( xTimerHandle xTimer );". + * + * @return If the timer is successfully create then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then 0 is returned. + * + * Example usage: + * + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * xTimerHandle xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * long lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( xTimerHandle pxTimer ) + * { + * long lArrayIndex; + * const long xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; + +/** + * void *pvTimerGetTimerID( xTimerHandle xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used within the callback function to identify which timer actually + * expired. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired on-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * + * // This function assumes xTimer has already been created. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + */ +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * xTimerGetTimerDaemonTaskHandle() is only available if + * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); + +/** + * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xBlockTime is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xBlockTime ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * xTimerHandle xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c old mode 100644 new mode 100755 index ab9699602..9ae5d86e4 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c @@ -1,191 +1,204 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem *pxIterator; -portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex-M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ -xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem *pxIterator; +portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ +xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c old mode 100644 new mode 100755 index 4e8976db9..4748860db --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c @@ -1,1536 +1,1682 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#if ( configUSE_CO_ROUTINES == 1 ) - #include "croutine.h" -#endif - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and cTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0U ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ - taskENTER_CRITICAL(); \ - { \ - if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL() -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; -xQueueHandle xReturn = NULL; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->pcWriteTo = pxNewQueue->pcHead; - pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - ( unsigned portBASE_TYPE ) 1U ) * uxItemSize ); - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Likewise ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceQUEUE_CREATE( pxNewQueue ); - xReturn = pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED(); - vPortFree( pxNewQueue ); - } - } - } - - configASSERT( xReturn ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( void ) - { - xQUEUE *pxNewQueue; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; - pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); - - traceCREATE_MUTEX( pxNewQueue ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - configASSERT( pxNewQueue ); - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - else - { - traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - configASSERT( pxHandle ); - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( pxHigherPriorityTaskWoken ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( pxTaskWoken ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - *pxTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - configASSERT( pxQueue ); - - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( xCoRoutinePreviouslyWoken == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( ( *pxCoRoutineWoken ) == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) - { - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements. - It can result in vListInsert() being called on a list that can only - possibly ever have one item in it, so the list will be fast, but even - so it should be called with the scheduler locked and not from a critical - section. */ - - /* Only do anything if there are no messages in the queue. This function - will not actually cause the task to block, just place it on a blocked - list. It will not block until the scheduler is unlocked - at which - time a yield will be performed. If an item is added to the queue while - the queue is locked, and the calling task blocks on the queue, then the - calling task will be immediately unblocked when the queue is unlocked. */ - prvLockQueue( pxQueue ); - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) - { - /* There is nothing in the queue, block for the specified period. */ - vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - } - prvUnlockQueue( pxQueue ); - } - -#endif - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and xTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0U ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) + +/* These definitions *must* match those in queue.h. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + volatile signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned char ucQueueNumber; + unsigned char ucQueueType; + #endif + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) PRIVILEGED_FUNCTION; +xTaskHandle xQueueGetMutexHolder( xQueueHandle xSemaphore ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) +{ + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); + pxQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxQueue->pcWriteTo = pxQueue->pcHead; + pxQueue->pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( unsigned portBASE_TYPE ) 1U ) * pxQueue->uxItemSize ); + pxQueue->xRxLock = queueUNLOCKED; + pxQueue->xTxLock = queueUNLOCKED; + + if( xNewQueue == pdFALSE ) + { + /* If there are tasks blocked waiting to read from the queue, then + the tasks will remain blocked as after this function exits the queue + will still be empty. If there are tasks blocked waiting to write to + the queue, then one should be unblocked as after this function exits + it will be possible to write to it. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + /* Ensure the event queues start in the correct state. */ + vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); + } + } + taskEXIT_CRITICAL(); + + /* A value is returned for calling semantic consistency with previous + versions. */ + return pdPASS; +} +/*-----------------------------------------------------------*/ + +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; +xQueueHandle xReturn = NULL; + + /* Remove compiler warnings about unused parameters should + configUSE_TRACE_FACILITY not be set to 1. */ + ( void ) ucQueueType; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + xQueueGenericReset( pxNewQueue, pdTRUE ); + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif /* configUSE_TRACE_FACILITY */ + + traceQUEUE_CREATE( pxNewQueue ); + xReturn = pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + vPortFree( pxNewQueue ); + } + } + } + + configASSERT( xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) + { + xQUEUE *pxNewQueue; + + /* Prevent compiler warnings about unused parameters if + configUSE_TRACE_FACILITY does not equal 1. */ + ( void ) ucQueueType; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; + pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceCREATE_MUTEX( pxNewQueue ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + configASSERT( pxNewQueue ); + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xQueueGetMutexHolder == 1 ) ) + + void* xQueueGetMutexHolder( xQueueHandle xSemaphore ) + { + void *pxReturn; + + /* This function is called by xSemaphoreGetMutexHolder(), and should not + be called directly. Note: This is is a good way of determining if the + calling task is the mutex holder, but not a good way of determining the + identity of the mutex holder, as the holder may change between the + following critical section exiting and the function returning. */ + taskENTER_CRITICAL(); + { + if( xSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = ( void * ) xSemaphore->pxMutexHolder; + } + else + { + pxReturn = NULL; + } + } + taskEXIT_CRITICAL(); + + return pxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueGenericCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + configASSERT( pxHandle ); + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + configASSERT( pxQueue ); + + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) + { + pxQueue->ucQueueNumber = ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueType; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( xCoRoutinePreviouslyWoken == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( ( *pxCoRoutineWoken ) == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) + { + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + } + prvUnlockQueue( pxQueue ); + } + +#endif + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c old mode 100644 new mode 100755 index 89ab31af4..0c43e63d6 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c @@ -1,2521 +1,2480 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "timers.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5U ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255U; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing != pdFALSE ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ - if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = ( pxTCB )->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -portTickType xItemValue; \ - \ - /* Is the tick count greater than or equal to the wake time of the first \ - task referenced from the delayed tasks list? */ \ - if( xTickCount >= xNextTaskUnblockTime ) \ - { \ - for( ;; ) \ - { \ - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ - { \ - /* The delayed list is empty. Set xNextTaskUnblockTime to the \ - maximum possible value so it is extremely unlikely that the \ - if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ - time through. */ \ - xNextTaskUnblockTime = portMAX_DELAY; \ - break; \ - } \ - else \ - { \ - /* The delayed list is not empty, get the value of the item at \ - the head of the delayed list. This is the time at which the \ - task at the head of the delayed list should be removed from \ - the Blocked state. */ \ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ - xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ - \ - if( xTickCount < xItemValue ) \ - { \ - /* It is not time to unblock this item yet, but the item \ - value is the time at which the task at the head of the \ - blocked list should be removed from the Blocked state - \ - so record the item value in xNextTaskUnblockTime. */ \ - xNextTaskUnblockTime = xItemValue; \ - break; \ - } \ - \ - /* It is time to remove the item from the Blocked state. */ \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer != NULL ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ - } \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) - -/* Callback function prototypes. --------------------------*/ -extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); -extern void vApplicationTickHook( void ); - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * The currently executing task is entering the Blocked state. Add the task to - * either the current or the overflow delayed task list. - */ -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - configASSERT( pxTaskCode ); - configASSERT( ( uxPriority < configMAX_PRIORITIES ) ); - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); - - /* Check the alignment of the calculated top of stack is correct. */ - configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* Check the alignment of the stack buffer is correct. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters ); - } - #endif - - /* Check the alignment of the initialised stack. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - taskENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( pxCurrentTCB == NULL ) - { - /* There are no other tasks, or all the other tasks are in - the suspended state - make this the current task. */ - pxCurrentTCB = pxNewTCB; - - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - taskEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED(); - } - - if( xReturn == pdPASS ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - taskEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - configASSERT( pxPreviousWakeTime ); - configASSERT( ( xTimeIncrement > 0U ) ); - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay != pdFALSE ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0U ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - taskEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority; - portBASE_TYPE xYieldRequired = pdFALSE; - - configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - taskENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - taskEXIT_CRITICAL(); - - if( ( void * ) pxTaskToSuspend == NULL ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* We have just suspended the current task. */ - portYIELD_WITHIN_API(); - } - else - { - /* The scheduler is not running, but the task that was pointed - to by pxCurrentTCB has just been suspended and pxCurrentTCB - must be adjusted to point to a different task. */ - if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) - { - /* No other tasks are ready, so set pxCurrentTCB back to - NULL so when the next task is created pxCurrentTCB will - be set to point to it no matter what its relative priority - is. */ - pxCurrentTCB = NULL; - } - else - { - vTaskSwitchContext(); - } - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* It does not make sense to check if the calling task is suspended. */ - configASSERT( xTask ); - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* It does not make sense to resume the calling task. */ - configASSERT( pxTaskToResume ); - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - taskENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - configASSERT( pxTaskToResume ); - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - { - /* Create the idle task, storing its handle in xIdleTaskHandle so it can - be returned by the xTaskGetIdleTaskHandle() function. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); - } - #else - { - /* Create the idle task without storing its handle. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); - } - #endif - - #if ( configUSE_TIMERS == 1 ) - { - if( xReturn == pdPASS ) - { - xReturn = xTimerCreateTimerTask(); - } - } - #endif - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0U; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() != pdFALSE ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } - - /* This line will only be reached if the kernel could not be started. */ - configASSERT( xReturn ); -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* If uxSchedulerSuspended is zero then this function does not match a - previous call to vTaskSuspendAll(). */ - configASSERT( uxSchedulerSuspended ); - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - taskENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - taskEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - taskENTER_CRITICAL(); - { - xTicks = xTickCount; - } - taskEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -portTickType xTaskGetTickCountFromISR( void ) -{ -portTickType xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - xReturn = xTickCount; - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_pcTaskGetTaskName == 1 ) - - signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) - { - tskTCB *pxTCB; - - /* If null is passed in here then the name of the calling task is being queried. */ - pxTCB = prvGetTCBFromHandle( xTaskToQuery ); - configASSERT( pxTCB ); - return &( pxTCB->pcTaskName[ 0 ] ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); - #else - ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Divide ulTotalRunTime by 100 to make the percentage caluclations - simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ - ulTotalRunTime /= 100UL; - - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - configASSERT( pcBuffer ); - configASSERT( ulBufferSize ); - - taskENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - taskEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - taskENTER_CRITICAL(); - xTracing = pdFALSE; - taskEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif -/*----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - xTaskHandle xTaskGetIdleTaskHandle( void ) - { - /* If xTaskGetIdleTaskHandle() is called before the scheduler has been - started, then xIdleTaskHandle will be NULL. */ - configASSERT( ( xIdleTaskHandle != NULL ) ); - return xIdleTaskHandle; - } - -#endif - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - -void vTaskIncrementTick( void ) -{ -tskTCB * pxTCB; - - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0U ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); - - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) - { - /* The new current delayed list is empty. Set - xNextTaskUnblockTime to the maximum possible value so it is - extremely unlikely that the - if( xTickCount >= xNextTaskUnblockTime ) test will pass until - there is an item in the delayed list. */ - xNextTaskUnblockTime = portMAX_DELAY; - } - else - { - /* The new current delayed list is not empty, get the value of - the item at the head of the delayed list. This is the time at - which the task at the head of the delayed list should be removed - from the Blocked state. */ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); - xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); - } - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xTCB->pxTaskTag = pxHookFunction; - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - taskEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - } - else - { - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter; - - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); - #else - ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - configASSERT( uxTopReadyPriority ); - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); - } -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - #endif -} -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) - { - portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements - - it should be called from a critical section. */ - - - /* Place the event list item of the TCB in the appropriate event list. - In this case it is assume that this is the only task that is going to - be waiting on this event list, so the faster vListInsertEnd() function - can be used in place of vListInsert. */ - vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove this task from the ready list before adding it to the - blocked list as the same list item is used for both lists. This - function is called form a critical section. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - -#endif /* configUSE_TIMERS */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. - - This function assumes that a check has already been made to ensure that - pxEventList is not empty. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - configASSERT( pxUnblockedTCB ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - configASSERT( pxTimeOut ); - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - configASSERT( pxTimeOut ); - configASSERT( pxTicksToWait ); - - taskENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( xListIsEmpty == pdFALSE ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - taskEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) -{ - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* If the task entering the blocked state was placed at the head of the - list of blocked tasks then xNextTaskUnblockTime needs to be updated - too. */ - if( xTimeToWake < xNextTaskUnblockTime ) - { - xNextTaskUnblockTime = xTimeToWake; - } - } -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0UL ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time has the task used? - This will always be rounded down to the nearest integer. - ulTotalRunTime has already been divided by 100. */ - ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - #endif - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - #endif - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetRunTime == 1 ) - - unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) - { - unsigned long runTime; - - tskTCB *pxTCB; - pxTCB = prvGetTCBFromHandle( xTask ); - runTime = pxTCB->ulRunTimeCounter; - pxTCB->ulRunTimeCounter = 0; - return runTime; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0U; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - configASSERT( pxMutexHolder ); - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - ( pxCurrentTCB->uxCriticalNesting )++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0U ) - { - ( pxCurrentTCB->uxCriticalNesting )--; - - if( pxCurrentTCB->uxCriticalNesting == 0U ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#include +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "StackMacros.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Macro to define the amount of stack available to the idle task. + */ +#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE + +/* + * Task control block. A task control block (TCB) is allocated to each task, + * and stores the context of the task. + */ +typedef struct tskTaskControlBlock +{ + volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ + #endif + + xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ + portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ + signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ + + #if ( portSTACK_GROWTH > 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ + unsigned portBASE_TYPE uxTaskNumber; /*< This stores a number specifically for use by third party trace code. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/*lint -e956 */ +PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. --------------------*/ + +PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ + +#if ( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; + +#endif + +/* File private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + PRIVILEGED_DATA static char pcStatsString[ 50 ] ; + PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; + +#endif + +/* Debugging and trace facilities private variables and macros. ------------*/ + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) +#define tskREADY_CHAR ( ( signed char ) 'R' ) +#define tskDELETED_CHAR ( ( signed char ) 'D' ) +#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) + +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready queue for + * the task. It is inserted at the end of the list. One quirk of this is + * that if the task being inserted is at the same priority as the currently + * executing task, then it will only be rescheduled after the currently + * executing task has been rescheduled. + */ +#define prvAddTaskToReadyQueue( pxTCB ) \ + traceMOVED_TASK_TO_READY_STATE( pxTCB ) \ + if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( pxTCB )->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) +/*-----------------------------------------------------------*/ + +/* + * Macro that looks at the list of tasks that are currently delayed to see if + * any require waking. + * + * Tasks are stored in the queue in the order of their wake time - meaning + * once one tasks has been found whose timer has not expired we need not look + * any further down the list. + */ +#define prvCheckDelayedTasks() \ +{ \ +portTickType xItemValue; \ + \ + /* Is the tick count greater than or equal to the wake time of the first \ + task referenced from the delayed tasks list? */ \ + if( xTickCount >= xNextTaskUnblockTime ) \ + { \ + for( ;; ) \ + { \ + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ + { \ + /* The delayed list is empty. Set xNextTaskUnblockTime to the \ + maximum possible value so it is extremely unlikely that the \ + if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ + time through. */ \ + xNextTaskUnblockTime = portMAX_DELAY; \ + break; \ + } \ + else \ + { \ + /* The delayed list is not empty, get the value of the item at \ + the head of the delayed list. This is the time at which the \ + task at the head of the delayed list should be removed from \ + the Blocked state. */ \ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ + \ + if( xTickCount < xItemValue ) \ + { \ + /* It is not time to unblock this item yet, but the item \ + value is the time at which the task at the head of the \ + blocked list should be removed from the Blocked state - \ + so record the item value in xNextTaskUnblockTime. */ \ + xNextTaskUnblockTime = xItemValue; \ + break; \ + } \ + \ + /* It is time to remove the item from the Blocked state. */ \ + vListRemove( &( pxTCB->xGenericListItem ) ); \ + \ + /* Is the task waiting on an event also? */ \ + if( pxTCB->xEventListItem.pvContainer != NULL ) \ + { \ + vListRemove( &( pxTCB->xEventListItem ) ); \ + } \ + prvAddTaskToReadyQueue( pxTCB ); \ + } \ + } \ + } \ +} +/*-----------------------------------------------------------*/ + +/* + * Several functions take an xTaskHandle parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) + +/* Callback function prototypes. --------------------------*/ +extern void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName ); +extern void vApplicationTickHook( void ); + +/* File private functions. --------------------------------*/ + +/* + * Utility to ready a TCB for a given task. Mainly just copies the parameters + * into the TCB structure. + */ +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; + +/* + * Allocates memory from the heap for a TCB and associated stack. Checks the + * allocation was successful. + */ +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; + +/* + * Called from vTaskList. vListTasks details all the tasks currently under + * control of the scheduler. The tasks may be in one of a number of lists. + * prvListTaskWithinSingleList accepts a list and details the tasks from + * within just that list. + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + + +/*lint +e956 */ + + + +/*----------------------------------------------------------- + * TASK CREATION API documented in task.h + *----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) +{ +signed portBASE_TYPE xReturn; +tskTCB * pxNewTCB; + + configASSERT( pxTaskCode ); + configASSERT( ( ( uxPriority & ( ~portPRIVILEGE_BIT ) ) < configMAX_PRIORITIES ) ); + + /* Allocate the memory required by the TCB and stack for the new task, + checking that the allocation was successful. */ + pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); + + if( pxNewTCB != NULL ) + { + portSTACK_TYPE *pxTopOfStack; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + portBASE_TYPE xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Calculate the top of stack address. This depends on whether the + stack grows from high memory to low (as per the 80x86) or visa versa. + portSTACK_GROWTH is used to make the result positive or negative as + required by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + } + #else + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* If we want to use stack checking on architectures that use + a positive stack growth direction then we also need to store the + other extreme of the stack space. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + } + #endif + + /* Setup the newly allocated TCB with the initial state of the task. */ + prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif + + /* Check the alignment of the initialised stack. */ + portALIGNMENT_ASSERT_pxCurrentTCB( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + if( ( void * ) pxCreatedTask != NULL ) + { + /* Pass the TCB out - in an anonymous way. The calling function/ + task can use this as a handle to delete the task later if + required.*/ + *pxCreatedTask = ( xTaskHandle ) pxNewTCB; + } + + /* We are going to manipulate the task queues to add this task to a + ready list, so must make sure no interrupts occur. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + } + } + + /* Remember the top priority to make context switching faster. Use + the priority in pxNewTCB as this has been capped to a valid value. */ + if( pxNewTCB->uxPriority > uxTopUsedPriority ) + { + uxTopUsedPriority = pxNewTCB->uxPriority; + } + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif + uxTaskNumber++; + + prvAddTaskToReadyQueue( pxNewTCB ); + + xReturn = pdPASS; + portSETUP_TCB( pxNewTCB ); + traceTASK_CREATE( pxNewTCB ); + } + taskEXIT_CRITICAL(); + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + traceTASK_CREATE_FAILED(); + } + + if( xReturn == pdPASS ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < uxPriority ) + { + portYIELD_WITHIN_API(); + } + } + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( xTaskHandle pxTaskToDelete ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + deleted. */ + if( pxTaskToDelete == pxCurrentTCB ) + { + pxTaskToDelete = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); + + /* Remove task from the ready list and place in the termination list. + This will stop the task from be scheduled. The idle task will check + the termination list and free up any memory allocated by the + scheduler for the TCB and stack. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxTasksDeleted; + + /* Increment the uxTaskNumberVariable also so kernel aware debuggers + can detect that the task lists need re-generating. */ + uxTaskNumber++; + + traceTASK_DELETE( pxTCB ); + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if we have just deleted the current task. */ + if( xSchedulerRunning != pdFALSE ) + { + if( ( void * ) pxTaskToDelete == NULL ) + { + portYIELD_WITHIN_API(); + } + } + } + +#endif + + + + + + +/*----------------------------------------------------------- + * TASK CONTROL API documented in task.h + *----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) + { + portTickType xTimeToWake; + portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0U ) ); + + vTaskSuspendAll(); + { + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL(); + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( portTickType xTicksToDelay ) + { + portTickType xTimeToWake; + signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( portTickType ) 0U ) + { + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + xAlreadyYielded = xTaskResumeAll(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxCurrentPriority; + portBASE_TYPE xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= configMAX_PRIORITIES ) + { + uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + taskENTER_CRITICAL(); + { + if( pxTask == pxCurrentTCB ) + { + pxTask = NULL; + } + + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + + traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentPriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentPriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentPriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentPriority ) + { + if( pxTask != NULL ) + { + /* The priority of another task is being raised. If we + were raising the priority of the currently running task + there would be no need to switch as it must have already + been the highest priority task. */ + xYieldRequired = pdTRUE; + } + } + else if( pxTask == NULL ) + { + /* Setting our own priority down means there may now be another + task of higher priority that is ready to execute. */ + xYieldRequired = pdTRUE; + } + + + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); + + /* If the task is in the blocked or suspended list we need do + nothing more than change it's priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the queue appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + /* The task is currently in its ready list - remove before adding + it to it's new ready list. As we are in a critical section we + can do this even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + + if( xYieldRequired == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( xTaskHandle pxTaskToSuspend ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + suspended. */ + if( pxTaskToSuspend == pxCurrentTCB ) + { + pxTaskToSuspend = NULL; + } + + /* If null is passed in here then we are suspending ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the suspended list. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); + } + taskEXIT_CRITICAL(); + + if( ( void * ) pxTaskToSuspend == NULL ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* We have just suspended the current task. */ + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) + { + portBASE_TYPE xReturn = pdFALSE; + const tskTCB * const pxTCB = ( tskTCB * ) xTask; + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task we are attempting to resume actually in the + suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) + { + /* Is it in the suspended list because it is in the + Suspended state? It is possible to be in the suspended + list because it is blocked on a task with no timeout + specified. */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) + { + xReturn = pdTRUE; + } + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( xTaskHandle pxTaskToResume ) + { + tskTCB *pxTCB; + + /* It does not make sense to resume the calling task. */ + configASSERT( pxTaskToResume ); + + /* Remove the task from whichever list it is currently in, and place + it in the ready list. */ + pxTCB = ( tskTCB * ) pxTaskToResume; + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) + { + taskENTER_CRITICAL(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME( pxTCB ); + + /* As we are in a critical section we can access the ready + lists even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* We may have just resumed a higher priority task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, but + will leave the lists in the correct state for the next yield. */ + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + tskTCB *pxTCB; + unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxTaskToResume ); + + pxTCB = ( tskTCB * ) pxTaskToResume; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xYieldRequired; + } + +#endif + + + + +/*----------------------------------------------------------- + * PUBLIC SCHEDULER CONTROL documented in task.h + *----------------------------------------------------------*/ + + +void vTaskStartScheduler( void ) +{ +portBASE_TYPE xReturn; + + /* Add the idle task at the lowest priority. */ + #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + { + /* Create the idle task, storing its handle in xIdleTaskHandle so it can + be returned by the xTaskGetIdleTaskHandle() function. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); + } + #else + { + /* Create the idle task without storing its handle. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); + } + #endif + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + } + #endif + + if( xReturn == pdPASS ) + { + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. + + STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE + DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ + portDISABLE_INTERRUPTS(); + + xSchedulerRunning = pdTRUE; + xTickCount = ( portTickType ) 0U; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() != pdFALSE ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + + /* This line will only be reached if the kernel could not be started. */ + configASSERT( xReturn ); +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + portBASE_TYPE. */ + ++uxSchedulerSuspended; +} +/*----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskResumeAll( void ) +{ +register tskTCB *pxTCB; +signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); + vListRemove( &( pxTCB->xEventListItem ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* If we have moved a task that has a priority higher than + the current task then we should yield. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does not + slip, and that any delayed tasks are resumed at the correct time. */ + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskIncrementTick(); + --uxMissedTicks; + } + + /* As we have processed some ticks it is appropriate to yield + to ensure the highest priority task that is ready to run is + the task actually running. */ + #if configUSE_PREEMPTION == 1 + { + xYieldRequired = pdTRUE; + } + #endif + } + + if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) + { + xAlreadyYielded = pdTRUE; + xMissedYield = pdFALSE; + portYIELD_WITHIN_API(); + } + } + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} + + + + + + +/*----------------------------------------------------------- + * PUBLIC TASK UTILITIES documented in task.h + *----------------------------------------------------------*/ + + + +portTickType xTaskGetTickCount( void ) +{ +portTickType xTicks; + + /* Critical section required if running on a 16 bit processor. */ + taskENTER_CRITICAL(); + { + xTicks = xTickCount; + } + taskEXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +portTickType xTaskGetTickCountFromISR( void ) +{ +portTickType xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + xReturn = xTickCount; + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + portBASE_TYPE. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_pcTaskGetTaskName == 1 ) + + signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) + { + tskTCB *pxTCB; + + /* If null is passed in here then the name of the calling task is being queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskList( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB and + report the task name, state and stack high water mark. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); + } + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + unsigned long ulTotalRunTime; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Divide ulTotalRunTime by 100 to make the percentage caluclations + simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ + ulTotalRunTime /= 100UL; + + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); + } + + #if ( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + xTaskHandle xTaskGetIdleTaskHandle( void ) + { + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; + } + +#endif + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + * documented in task.h + *----------------------------------------------------------*/ + +void vTaskIncrementTick( void ) +{ +tskTCB * pxTCB; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + ++xTickCount; + if( xTickCount == ( portTickType ) 0U ) + { + xList *pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. + If there are any items in pxDelayedTaskList here then there is + an error! */ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); + + pxTemp = pxDelayedTaskList; + pxDelayedTaskList = pxOverflowDelayedTaskList; + pxOverflowDelayedTaskList = pxTemp; + xNumOfOverflows++; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set + xNextTaskUnblockTime to the maximum possible value so it is + extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); + } + } + + /* See if this tick has made a timeout expire. */ + prvCheckDelayedTasks(); + } + else + { + ++uxMissedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the missed tick + count is being unwound (when the scheduler is being unlocked. */ + if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) + { + vApplicationTickHook(); + } + } + #endif + + traceTASK_INCREMENT_TICK( xTickCount ); +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) + { + tskTCB *xTCB; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xTCB->pxTaskTag = pxHookFunction; + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) + { + tskTCB *xTCB; + pdTASK_HOOK_CODE xReturn; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xReturn = xTCB->pxTaskTag; + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) + { + tskTCB *xTCB; + portBASE_TYPE xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xMissedYield = pdTRUE; + } + else + { + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + unsigned long ulTempCounter; + + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); + #else + ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the accumulated + time so far. The time the task started running was stored in + ulTaskSwitchedInTime. Note that there is no overflow protection here + so count values are only valid until the timer overflows. Generally + this will be about 1 hour assuming a 1uS timer increment. */ + pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); + ulTaskSwitchedInTime = ulTempCounter; + } + #endif + + taskFIRST_CHECK_FOR_STACK_OVERFLOW(); + taskSECOND_CHECK_FOR_STACK_OVERFLOW(); + + /* Find the highest priority queue that contains ready tasks. */ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) + { + configASSERT( uxTopReadyPriority ); + --uxTopReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the + same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); + + traceTASK_SWITCHED_IN(); + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) +{ +portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. */ + vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove ourselves from the ready list before adding ourselves + to the blocked list as the same list item is used for both lists. We have + exclusive access to the ready lists as the scheduler is locked. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( xTicksToWait == portMAX_DELAY ) + { + /* Add ourselves to the suspended task list instead of a delayed task + list to ensure we are not woken by a timing event. We will block + indefinitely. */ + vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + #else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + #endif +} +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) + { + portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called from a critical section. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove this task from the ready list before adding it to the + blocked list as the same list item is used for both lists. This + function is called form a critical section. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) +{ +tskTCB *pxUnblockedTCB; +portBASE_TYPE xReturn; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. It can also be called from within an ISR. */ + + /* The event list is sorted in priority order, so we can remove the + first in the list, remove the TCB from the delayed list, and add + it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means we can always expect exclusive access to the event list here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + configASSERT( pxUnblockedTCB ); + vListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxUnblockedTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has + a higher priority than the calling task. This allows + the calling task to know if it should force a context + switch now. */ + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) +{ +portBASE_TYPE xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + #if ( INCLUDE_vTaskSuspend == 1 ) + /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is + the maximum block time then the task should block indefinitely, and + therefore never time out. */ + if( *pxTicksToWait == portMAX_DELAY ) + { + xReturn = pdFALSE; + } + else /* We are not blocking indefinitely, perform the checks below. */ + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) + { + /* The tick count is greater than the time at which vTaskSetTimeout() + was called, but has also overflowed since vTaskSetTimeOut() was called. + It must have wrapped all the way around and gone past us again. This + passed since vTaskSetTimeout() was called. */ + xReturn = pdTRUE; + } + else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); + vTaskSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xMissedYield = pdTRUE; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ) + { + unsigned portBASE_TYPE uxReturn; + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + uxReturn = pxTCB->uxTaskNumber; + } + else + { + uxReturn = 0U; + } + + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ) + { + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + pxTCB->uxTaskNumber = uxHandle; + } + } +#endif + + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* See if any tasks have been deleted. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) + { + taskYIELD(); + } + } + #endif + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif + } +} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ + + + + + + + +/*----------------------------------------------------------- + * File private functions documented at the top of the file. + *----------------------------------------------------------*/ + + + +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) +{ + /* Store the function name in the TCB. */ + #if configMAX_TASK_NAME_LEN > 1 + { + /* Don't bring strncpy into the build unnecessarily. */ + strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); + } + #endif + pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= configMAX_PRIORITIES ) + { + uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + pxTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxTCB->uxBasePriority = uxPriority; + } + #endif + + vListInitialiseItem( &( pxTCB->xGenericListItem ) ); + vListInitialiseItem( &( pxTCB->xEventListItem ) ); + + /* Set the pxTCB as a link back from the xListItem. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; + } + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxTCB->pxTaskTag = NULL; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTCB->ulRunTimeCounter = 0UL; + } + #endif + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); + } + #else + { + ( void ) xRegions; + ( void ) usStackDepth; + } + #endif +} +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) + { + tskTCB *pxTCB; + + if( xTaskToModify == pxCurrentTCB ) + { + xTaskToModify = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + /*-----------------------------------------------------------*/ +#endif + +static void prvInitialiseTaskLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedTaskList1 ); + vListInitialise( ( xList * ) &xDelayedTaskList2 ); + vListInitialise( ( xList * ) &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( ( xList * ) &xTasksWaitingTermination ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( ( xList * ) &xSuspendedTaskList ); + } + #endif + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + #if ( INCLUDE_vTaskDelete == 1 ) + { + portBASE_TYPE xListIsEmpty; + + /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called + too often in the idle task. */ + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskSuspendAll(); + xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); + xTaskResumeAll(); + + if( xListIsEmpty == pdFALSE ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + --uxCurrentNumberOfTasks; + --uxTasksDeleted; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + } + #endif +} +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) +{ + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + } +} +/*-----------------------------------------------------------*/ + +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) +{ +tskTCB *pxNewTCB; + + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function. */ + pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + else + { + /* Just to help debugging. */ + memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); + } + } + + return pxNewTCB; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned short usStackRemaining; + PRIVILEGED_DATA static char pcStatusString[ configMAX_TASK_NAME_LEN + 30 ]; + + /* Write the details of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + #if ( portSTACK_GROWTH > 0 ) + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); + } + #else + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); + } + #endif + + sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned long ulStatsAsPercentage; + + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + + /* Divide by zero check. */ + if( ulTotalRunTime > 0UL ) + { + /* Has the task run at all? */ + if( pxNextTCB->ulRunTimeCounter == 0UL ) + { + /* The task has used no CPU time at all. */ + sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); + } + else + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTime has already been divided by 100. */ + ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); + } + #endif + } + } + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) + { + register unsigned short usCount = 0U; + + while( *pucStackByte == tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + usCount++; + } + + usCount /= sizeof( portSTACK_TYPE ); + + return usCount; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) + { + tskTCB *pxTCB; + unsigned char *pcEndOfStack; + unsigned portBASE_TYPE uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; + } + #else + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) + { + /* This call is required specifically for the TriCore port. It must be + above the vPortFree() calls. The call is also used by ports/demos that + want to allocate and clean RAM statically. */ + portCLEAN_UP_TCB( pxTCB ); + + /* Free up the memory allocated by the scheduler for the task. It is up to + the task to free any memory allocated at the application level. */ + vPortFreeAligned( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + +#endif + + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + xTaskHandle xTaskGetCurrentTaskHandle( void ) + { + xTaskHandle xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + portBASE_TYPE xTaskGetSchedulerState( void ) + { + portBASE_TYPE xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + configASSERT( pxMutexHolder ); + + if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new priority. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); + + /* If the task being modified is in the ready state it will need to + be moved in to a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Inherit the priority before being moved into the new list. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* Just inherit the priority. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + } + + traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority ); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxMutexHolder != NULL ) + { + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* We must be the running task to be able to give the mutex back. + Remove ourselves from the ready list we currently appear in. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Disinherit the priority before adding the task into the new + ready list. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + pxTCB->uxPriority = pxTCB->uxBasePriority; + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); + prvAddTaskToReadyQueue( pxTCB ); + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + +void vTaskExitCritical( void ) +{ + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0U ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0U ) + { + portENABLE_INTERRUPTS(); + } + } + } +} + +#endif +/*-----------------------------------------------------------*/ + + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c old mode 100644 new mode 100755 index 2d8ce293b..0be294277 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c @@ -1,673 +1,686 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "timers.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. This #if is closed at the very bottom -of this file. If you want to include software timer functionality then ensure -configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#if ( configUSE_TIMERS == 1 ) - -/* Misc definitions. */ -#define tmrNO_DELAY ( portTickType ) 0U - -/* The definition of the timers themselves. */ -typedef struct tmrTimerControl -{ - const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ - xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ - portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ - unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ - void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ - tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ -} xTIMER; - -/* The definition of messages that can be sent and received on the timer -queue. */ -typedef struct tmrTimerQueueMessage -{ - portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ - portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ - xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ -} xTIMER_MESSAGE; - - -/* The list in which active timers are stored. Timers are referenced in expire -time order, with the nearest expiry time at the front of the list. Only the -timer service task is allowed to access xActiveTimerList. */ -PRIVILEGED_DATA static xList xActiveTimerList1; -PRIVILEGED_DATA static xList xActiveTimerList2; -PRIVILEGED_DATA static xList *pxCurrentTimerList; -PRIVILEGED_DATA static xList *pxOverflowTimerList; - -/* A queue that is used to send commands to the timer service task. */ -PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Initialise the infrastructure used by the timer service task if it has not - * been initialised already. - */ -static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; - -/* - * The timer service task (daemon). Timer functionality is controlled by this - * task. Other tasks communicate with the timer service task using the - * xTimerQueue queue. - */ -static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; - -/* - * Called by the timer service task to interpret and process a command it - * received on the timer queue. - */ -static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; - -/* - * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, - * depending on if the expire time causes a timer counter overflow. - */ -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; - -/* - * An active timer has reached its expire time. Reload the timer if it is an - * auto reload timer, then call its callback. - */ -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; - -/* - * The tick count has overflowed. Switch the timer lists after ensuring the - * current timer list does not still reference some timers. - */ -static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; - -/* - * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE - * if a tick count overflow occurred since prvSampleTimeNow() was last called. - */ -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; - -/* - * If the timer list contains any active timers then return the expire time of - * the timer that will expire first and set *pxListWasEmpty to false. If the - * timer list does not contain any timers then return 0 and set *pxListWasEmpty - * to pdTRUE. - */ -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; - -/* - * If a timer has expired, process it. Otherwise, block the timer service task - * until either a timer does expire or a command is received. - */ -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; - -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerCreateTimerTask( void ) -{ -portBASE_TYPE xReturn = pdFAIL; - - /* This function is called when the scheduler is started if - configUSE_TIMERS is set to 1. Check that the infrastructure used by the - timer service task has been created/initialised. If timers have already - been created then the initialisation will already have been performed. */ - prvCheckForValidListAndQueue(); - - if( xTimerQueue != NULL ) - { - #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - { - /* Create the timer task, storing its handle in xTimerTaskHandle so - it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, &xTimerTaskHandle ); - } - #else - { - /* Create the timer task without storing its handle. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, NULL); - } - #endif - } - - configASSERT( xReturn ); - return xReturn; -} -/*-----------------------------------------------------------*/ - -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) -{ -xTIMER *pxNewTimer; - - /* Allocate the timer structure. */ - if( xTimerPeriodInTicks == ( portTickType ) 0U ) - { - pxNewTimer = NULL; - configASSERT( ( xTimerPeriodInTicks > 0 ) ); - } - else - { - pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); - if( pxNewTimer != NULL ) - { - /* Ensure the infrastructure used by the timer service task has been - created/initialised. */ - prvCheckForValidListAndQueue(); - - /* Initialise the timer structure members using the function parameters. */ - pxNewTimer->pcTimerName = pcTimerName; - pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; - pxNewTimer->uxAutoReload = uxAutoReload; - pxNewTimer->pvTimerID = pvTimerID; - pxNewTimer->pxCallbackFunction = pxCallbackFunction; - vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); - - traceTIMER_CREATE( pxNewTimer ); - } - else - { - traceTIMER_CREATE_FAILED(); - } - } - - return ( xTimerHandle ) pxNewTimer; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) -{ -portBASE_TYPE xReturn = pdFAIL; -xTIMER_MESSAGE xMessage; - - /* Send a message to the timer service task to perform a particular action - on a particular timer definition. */ - if( xTimerQueue != NULL ) - { - /* Send a command to the timer service task to start the xTimer timer. */ - xMessage.xMessageID = xCommandID; - xMessage.xMessageValue = xOptionalValue; - xMessage.pxTimer = ( xTIMER * ) xTimer; - - if( pxHigherPriorityTaskWoken == NULL ) - { - if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); - } - else - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); - } - } - else - { - xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); - } - - traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) - { - /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been - started, then xTimerTaskHandle will be NULL. */ - configASSERT( ( xTimerTaskHandle != NULL ) ); - return xTimerTaskHandle; - } - -#endif -/*-----------------------------------------------------------*/ - -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) -{ -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove the timer from the list of active timers. A check has already - been performed to ensure the list is not empty. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - traceTIMER_EXPIRED( pxTimer ); - - /* If the timer is an auto reload timer then calculate the next - expiry time and re-insert the timer in the list of active timers. */ - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* This is the only time a timer is inserted into a list using - a time relative to anything other than the current time. It - will therefore be inserted into the correct list relative to - the time this task thinks it is now, even if a command to - switch lists due to a tick count overflow is already waiting in - the timer queue. */ - if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Reload it now. */ - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - - /* Call the timer callback. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); -} -/*-----------------------------------------------------------*/ - -static void prvTimerTask( void *pvParameters ) -{ -portTickType xNextExpireTime; -portBASE_TYPE xListWasEmpty; - - /* Just to avoid compiler warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* Query the timers list to see if it contains any timers, and if so, - obtain the time at which the next timer will expire. */ - xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); - - /* If a timer has expired, process it. Otherwise, block this task - until either a timer does expire, or a command is received. */ - prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); - - /* Empty the command queue. */ - prvProcessReceivedCommands(); - } -} -/*-----------------------------------------------------------*/ - -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) -{ -portTickType xTimeNow; -portBASE_TYPE xTimerListsWereSwitched; - - vTaskSuspendAll(); - { - /* Obtain the time now to make an assessment as to whether the timer - has expired or not. If obtaining the time causes the lists to switch - then don't process this timer as any timers that remained in the list - when the lists were switched will have been processed within the - prvSampelTimeNow() function. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - if( xTimerListsWereSwitched == pdFALSE ) - { - /* The tick count has not overflowed, has the timer expired? */ - if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) - { - xTaskResumeAll(); - prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); - } - else - { - /* The tick count has not overflowed, and the next expire - time has not been reached yet. This task should therefore - block to wait for the next expire time or a command to be - received - whichever comes first. The following line cannot - be reached unless xNextExpireTime > xTimeNow, except in the - case when the current timer list is empty. */ - vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); - - if( xTaskResumeAll() == pdFALSE ) - { - /* Yield to wait for either a command to arrive, or the block time - to expire. If a command arrived between the critical section being - exited and this yield then the yield will not cause the task - to block. */ - portYIELD_WITHIN_API(); - } - } - } - else - { - xTaskResumeAll(); - } - } -} -/*-----------------------------------------------------------*/ - -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) -{ -portTickType xNextExpireTime; - - /* Timers are listed in expiry time order, with the head of the list - referencing the task that will expire first. Obtain the time at which - the timer with the nearest expiry time will expire. If there are no - active timers then just set the next expire time to 0. That will cause - this task to unblock when the tick count overflows, at which point the - timer lists will be switched and the next expiry time can be - re-assessed. */ - *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); - if( *pxListWasEmpty == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - } - else - { - /* Ensure the task unblocks when the tick count rolls over. */ - xNextExpireTime = ( portTickType ) 0U; - } - - return xNextExpireTime; -} -/*-----------------------------------------------------------*/ - -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) -{ -portTickType xTimeNow; -static portTickType xLastTime = ( portTickType ) 0U; - - xTimeNow = xTaskGetTickCount(); - - if( xTimeNow < xLastTime ) - { - prvSwitchTimerLists( xLastTime ); - *pxTimerListsWereSwitched = pdTRUE; - } - else - { - *pxTimerListsWereSwitched = pdFALSE; - } - - xLastTime = xTimeNow; - - return xTimeNow; -} -/*-----------------------------------------------------------*/ - -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) -{ -portBASE_TYPE xProcessTimerNow = pdFALSE; - - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - - if( xNextExpiryTime <= xTimeNow ) - { - /* Has the expiry time elapsed between the command to start/reset a - timer was issued, and the time the command was processed? */ - if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) - { - /* The time between a command being issued and the command being - processed actually exceeds the timers period. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); - } - } - else - { - if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) - { - /* If, since the command was issued, the tick count has overflowed - but the expiry time has not, then the timer must have already passed - its expiry time and should be processed immediately. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - } - - return xProcessTimerNow; -} -/*-----------------------------------------------------------*/ - -static void prvProcessReceivedCommands( void ) -{ -xTIMER_MESSAGE xMessage; -xTIMER *pxTimer; -portBASE_TYPE xTimerListsWereSwitched, xResult; -portTickType xTimeNow; - - /* In this case the xTimerListsWereSwitched parameter is not used, but it - must be present in the function call. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - - while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) - { - pxTimer = xMessage.pxTimer; - - /* Is the timer already in a list of active timers? When the command - is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the - command is to the task rather than to an individual timer. */ - if( pxTimer != NULL ) - { - if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) - { - /* The timer is in a list, remove it. */ - vListRemove( &( pxTimer->xTimerListItem ) ); - } - } - - traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); - - switch( xMessage.xMessageID ) - { - case tmrCOMMAND_START : - /* Start or restart a timer. */ - if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Process it now. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - break; - - case tmrCOMMAND_STOP : - /* The timer has already been removed from the active list. - There is nothing to do here. */ - break; - - case tmrCOMMAND_CHANGE_PERIOD : - pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; - configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); - prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); - break; - - case tmrCOMMAND_DELETE : - /* The timer has already been removed from the active list, - just free up the memory. */ - vPortFree( pxTimer ); - break; - - default : - /* Don't expect to get here. */ - break; - } - } -} -/*-----------------------------------------------------------*/ - -static void prvSwitchTimerLists( portTickType xLastTime ) -{ -portTickType xNextExpireTime, xReloadTime; -xList *pxTemp; -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove compiler warnings if configASSERT() is not defined. */ - ( void ) xLastTime; - - /* The tick count has overflowed. The timer lists must be switched. - If there are any timers still referenced from the current timer list - then they must have expired and should be processed before the lists - are switched. */ - while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - - /* Remove the timer from the list. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - - /* Execute its callback, then send a command to restart the timer if - it is an auto-reload timer. It cannot be restarted here as the lists - have not yet been switched. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* Calculate the reload value, and if the reload value results in - the timer going into the same timer list then it has already expired - and the timer should be re-inserted into the current list so it is - processed again within this loop. Otherwise a command should be sent - to restart the timer to ensure it is only inserted into a list after - the lists have been swapped. */ - xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); - if( xReloadTime > xNextExpireTime ) - { - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - else - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - } - - pxTemp = pxCurrentTimerList; - pxCurrentTimerList = pxOverflowTimerList; - pxOverflowTimerList = pxTemp; -} -/*-----------------------------------------------------------*/ - -static void prvCheckForValidListAndQueue( void ) -{ - /* Check that the list from which active timers are referenced, and the - queue used to communicate with the timer service, have been - initialised. */ - taskENTER_CRITICAL(); - { - if( xTimerQueue == NULL ) - { - vListInitialise( &xActiveTimerList1 ); - vListInitialise( &xActiveTimerList2 ); - pxCurrentTimerList = &xActiveTimerList1; - pxOverflowTimerList = &xActiveTimerList2; - xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); - } - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) -{ -portBASE_TYPE xTimerIsInActiveList; -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - /* Is the timer in the list of active timers? */ - taskENTER_CRITICAL(); - { - /* Checking to see if it is in the NULL list in effect checks to see if - it is referenced from either the current or the overflow timer lists in - one go, but the logic has to be reversed, hence the '!'. */ - xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); - } - taskEXIT_CRITICAL(); - - return xTimerIsInActiveList; -} -/*-----------------------------------------------------------*/ - -void *pvTimerGetTimerID( xTimerHandle xTimer ) -{ -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - return pxTimer->pvTimerID; -} -/*-----------------------------------------------------------*/ - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. If you want to include software timer -functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#endif /* configUSE_TIMERS == 1 */ +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( portTickType ) 0U + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl +{ + const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ + xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ +} xTIMER; + +/* The definition of messages that can be sent and received on the timer +queue. */ +typedef struct tmrTimerQueueMessage +{ + portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ + portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ +} xTIMER_MESSAGE; + + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access xActiveTimerList. */ +PRIVILEGED_DATA static xList xActiveTimerList1; +PRIVILEGED_DATA static xList xActiveTimerList2; +PRIVILEGED_DATA static xList *pxCurrentTimerList; +PRIVILEGED_DATA static xList *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerCreateTimerTask( void ) +{ +portBASE_TYPE xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + { + /* Create the timer task, storing its handle in xTimerTaskHandle so + it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle ); + } + #else + { + /* Create the timer task without storing its handle. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL); + } + #endif + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) +{ +xTIMER *pxNewTimer; + + /* Allocate the timer structure. */ + if( xTimerPeriodInTicks == ( portTickType ) 0U ) + { + pxNewTimer = NULL; + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + } + else + { + pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->uxAutoReload = uxAutoReload; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + + traceTIMER_CREATE( pxNewTimer ); + } + else + { + traceTIMER_CREATE_FAILED(); + } + } + + return ( xTimerHandle ) pxNewTimer; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) +{ +portBASE_TYPE xReturn = pdFAIL; +xTIMER_MESSAGE xMessage; + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.xMessageValue = xOptionalValue; + xMessage.pxTimer = ( xTIMER * ) xTimer; + + if( pxHigherPriorityTaskWoken == NULL ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) + { + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) +{ +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* This is the only time a timer is inserted into a list using + a time relative to anything other than the current time. It + will therefore be inserted into the correct list relative to + the time this task thinks it is now, even if a command to + switch lists due to a tick count overflow is already waiting in + the timer queue. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static void prvTimerTask( void *pvParameters ) +{ +portTickType xNextExpireTime; +portBASE_TYPE xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) +{ +portTickType xTimeNow; +portBASE_TYPE xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampelTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the block time + to expire. If a command arrived between the critical section being + exited and this yield then the yield will not cause the task + to block. */ + portYIELD_WITHIN_API(); + } + } + } + else + { + xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) +{ +portTickType xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( portTickType ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) +{ +portTickType xTimeNow; +PRIVILEGED_DATA static portTickType xLastTime = ( portTickType ) 0U; + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists( xLastTime ); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) +{ +portBASE_TYPE xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +xTIMER_MESSAGE xMessage; +xTIMER *pxTimer; +portBASE_TYPE xTimerListsWereSwitched, xResult; +portTickType xTimeNow; + + /* In this case the xTimerListsWereSwitched parameter is not used, but it + must be present in the function call. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) + { + pxTimer = xMessage.pxTimer; + + /* Is the timer already in a list of active timers? When the command + is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the + command is to the task rather than to an individual timer. */ + if( pxTimer != NULL ) + { + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) + { + /* The timer is in a list, remove it. */ + vListRemove( &( pxTimer->xTimerListItem ) ); + } + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + /* Start or restart a timer. */ + if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Process it now. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + break; + + case tmrCOMMAND_STOP : + /* The timer has already been removed from the active list. + There is nothing to do here. */ + break; + + case tmrCOMMAND_CHANGE_PERIOD : + pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + /* The timer has already been removed from the active list, + just free up the memory. */ + vPortFree( pxTimer ); + break; + + default : + /* Don't expect to get here. */ + break; + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( portTickType xLastTime ) +{ +portTickType xNextExpireTime, xReloadTime; +xList *pxTemp; +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove compiler warnings if configASSERT() is not defined. */ + ( void ) xLastTime; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) +{ +portBASE_TYPE xTimerIsInActiveList; +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + /* Checking to see if it is in the NULL list in effect checks to see if + it is referenced from either the current or the overflow timer lists in + one go, but the logic has to be reversed, hence the '!'. */ + xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); + } + taskEXIT_CRITICAL(); + + return xTimerIsInActiveList; +} +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( xTimerHandle xTimer ) +{ +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + return pxTimer->pvTimerID; +} +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h old mode 100644 new mode 100755 index e5eb39abb..c12f5d76f --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,11 +1,5 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. *************************************************************************** @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef INC_FREERTOS_H @@ -118,10 +125,6 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. #endif -#ifndef INCLUDE_vTaskCleanUpResources - #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - #ifndef INCLUDE_vTaskSuspend #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. #endif @@ -138,6 +141,22 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. #endif +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle + #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 +#endif + +#ifndef INCLUDE_xQueueGetMutexHolder + #define INCLUDE_xQueueGetMutexHolder 0 +#endif + +#ifndef INCLUDE_pcTaskGetTaskName + #define INCLUDE_pcTaskGetTaskName 0 +#endif + #ifndef configUSE_APPLICATION_TASK_TAG #define configUSE_APPLICATION_TASK_TAG 0 #endif @@ -190,6 +209,10 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); #define configASSERT( x ) #endif +#ifndef portALIGNMENT_ASSERT_pxCurrentTCB + #define portALIGNMENT_ASSERT_pxCurrentTCB configASSERT +#endif + /* The timers module relies on xTaskGetSchedulerState(). */ #if configUSE_TIMERS == 1 @@ -224,16 +247,26 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue #endif +#ifndef portCLEAN_UP_TCB + #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef portSETUP_TCB + #define portSETUP_TCB( pxTCB ) ( void ) pxTCB +#endif #ifndef configQUEUE_REGISTRY_SIZE #define configQUEUE_REGISTRY_SIZE 0U #endif -#if ( configQUEUE_REGISTRY_SIZE < 1U ) +#if ( configQUEUE_REGISTRY_SIZE < 1 ) #define vQueueAddToRegistry( xQueue, pcName ) #define vQueueUnregisterQueue( xQueue ) #endif +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE unsigned long +#endif /* Remove any unused trace macros. */ #ifndef traceSTART @@ -260,6 +293,23 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); #define traceTASK_SWITCHED_OUT() #endif +#ifndef traceTASK_PRIORITY_INHERIT + /* Called when a task attempts to take a mutex that is already held by a + lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task + that holds the mutex. uxInheritedPriority is the priority the mutex holder + will inherit (the priority of the task that is attempting to obtain the + muted. */ + #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) +#endif + +#ifndef traceTASK_PRIORITY_DISINHERIT + /* Called when a task releases a mutex, the holding of which had resulted in + the task inheriting the priority of a higher priority task. + pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the + mutex. uxOriginalPriority is the task's configured (base) priority. */ + #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) +#endif + #ifndef traceBLOCKING_ON_QUEUE_RECEIVE /* Task is about to block because it cannot read from a queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore @@ -282,12 +332,16 @@ typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); /* The following event macros are embedded in the kernel API calls. */ +#ifndef traceMOVED_TASK_TO_READY_STATE + #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + #ifndef traceQUEUE_CREATE #define traceQUEUE_CREATE( pxNewQueue ) #endif #ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED() + #define traceQUEUE_CREATE_FAILED( ucQueueType ) #endif #ifndef traceCREATE_MUTEX diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h old mode 100644 new mode 100755 index 1114b6d29..daf3ce408 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef STACK_MACROS_H diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h old mode 100644 new mode 100755 index 65fdc48e0..f2843cde2 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef CO_ROUTINE_H diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h old mode 100644 new mode 100755 index e8b47c439..28d4f248e --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ /* @@ -132,6 +139,15 @@ typedef struct xLIST */ #define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) +/* + * Access macro to get the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_OWNER( pxListItem ) ( pxListItem )->pvOwner + /* * Access macro to set the value of the list item. In most cases the value is * used to sort the list in descending order. @@ -142,7 +158,7 @@ typedef struct xLIST #define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) /* - * Access macro the retrieve the value of the list item. The value can + * Access macro to retrieve the value of the list item. The value can * represent anything - for example a the priority of a task, or the time at * which a task should be unblocked. * @@ -237,6 +253,13 @@ xList * const pxConstList = ( pxList ); \ */ #define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) +/* + * This provides a crude means of knowing if a list has been initialised, as + * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() + * function. + */ +#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) + /* * Must be called before a list is used! This initialises all the members * of the list structure and inserts the xListEnd item into the list as a diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h old mode 100644 new mode 100755 index b7371b9ba..be49c3d88 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef MPU_WRAPPERS_H @@ -85,8 +92,6 @@ only for ports that are using the MPU. */ #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks #define vTaskList MPU_vTaskList #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskStartTrace MPU_vTaskStartTrace - #define ulTaskEndTrace MPU_ulTaskEndTrace #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook @@ -94,7 +99,7 @@ only for ports that are using the MPU. */ #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - #define xQueueCreate MPU_xQueueCreate + #define xQueueGenericCreate MPU_xQueueGenericCreate #define xQueueCreateMutex MPU_xQueueCreateMutex #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h old mode 100644 new mode 100755 index 288320033..88cfbb2b7 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ /*----------------------------------------------------------- diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h old mode 100644 new mode 100755 index 37e432fec..c69db9237 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,22 +40,33 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef PROJDEFS_H #define PROJDEFS_H -void PIOS_DEBUG_PinValue8Bit(unsigned char value); - /* Defines the prototype to which task functions must conform. */ typedef void (*pdTASK_CODE)( void * ); @@ -79,9 +84,6 @@ typedef void (*pdTASK_CODE)( void * ); #define errQUEUE_BLOCKED ( -4 ) #define errQUEUE_YIELD ( -5 ) -// Uncomment this line to output the second character of the task that is being switched in on the debug-pins -//#define traceTASK_SWITCHED_IN() PIOS_DEBUG_PinValue8Bit(pxCurrentTCB->pcTaskName[1]); - #endif /* PROJDEFS_H */ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h old mode 100644 new mode 100755 index 47add266f..e48cf07a6 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ @@ -62,7 +69,7 @@ #define QUEUE_H #ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" + #error "include FreeRTOS.h" must appear in source files before "include queue.h" #endif #ifdef __cplusplus @@ -84,6 +91,12 @@ typedef void * xQueueHandle; #define queueSEND_TO_BACK ( 0 ) #define queueSEND_TO_FRONT ( 1 ) +/* For internal use only. These definitions *must* match those in queue.c. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) /** * queue. h @@ -141,7 +154,7 @@ typedef void * xQueueHandle; * \defgroup xQueueCreate xQueueCreate * \ingroup QueueManagement */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); +#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE ) /** * queue. h @@ -1174,10 +1187,10 @@ signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR * \ingroup QueueManagement */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ); /* - * Utilities to query queue that are safe to use from an ISR. These utilities + * Utilities to query queues that are safe to use from an ISR. These utilities * should be used only from witin an ISR, or within a critical section. */ signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); @@ -1221,11 +1234,13 @@ signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQue signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); /* - * For internal use only. Use xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting() instead of calling these functions directly. + * For internal use only. Use xSemaphoreCreateMutex(), + * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling + * these functions directly. */ -xQueueHandle xQueueCreateMutex( void ); +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ); xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); +void* xQueueGetMutexHolder( xQueueHandle xSemaphore ); /* * For internal use only. Use xSemaphoreTakeMutexRecursive() or @@ -1234,6 +1249,14 @@ xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); +/* + * Reset a queue back to its original empty state. pdPASS is returned if the + * queue is successfully reset. pdFAIL is returned if the queue could not be + * reset because there are tasks blocked on the queue waiting to either + * receive from the queue or send to the queue. + */ +#define xQueueReset( pxQueue ) xQueueGenericReset( pxQueue, pdFALSE ) + /* * The registry is provided as a means for kernel aware debuggers to * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add @@ -1258,8 +1281,15 @@ portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); #endif -/* Not a public API function, hence the 'Restricted' in the name. */ +/* + * Generic version of the queue creation function, which is in turn called by + * any queue, semaphore or mutex creation function or macro. + */ +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ); + +/* Not public API functions. */ void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ); #ifdef __cplusplus diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h old mode 100644 new mode 100755 index 0130f1d79..65c77c7c9 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,22 +40,35 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef SEMAPHORE_H #define SEMAPHORE_H #ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" + #error "include FreeRTOS.h" must appear in source files before "include semphr.h" #endif #include "queue.h" @@ -111,13 +118,14 @@ typedef xQueueHandle xSemaphoreHandle; * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary * \ingroup Semaphores */ -#define vSemaphoreCreateBinary( xSemaphore ) { \ - ( xSemaphore ) = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ - if( ( xSemaphore ) != NULL ) \ - { \ - xSemaphoreGive( ( xSemaphore ) ); \ - } \ - } +#define vSemaphoreCreateBinary( xSemaphore ) \ + { \ + ( xSemaphore ) = xQueueGenericCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } /** * semphr. h @@ -546,6 +554,40 @@ typedef xQueueHandle xSemaphoreHandle; */ #define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) +/** + * semphr. h + *
+ xSemaphoreTakeFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to take a semaphore from an ISR. The semaphore must have + * previously been created with a call to vSemaphoreCreateBinary() or + * xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR, however taking a semaphore from an ISR + * is not a common operation. It is likely to only be useful when taking a + * counting semaphore when an interrupt is obtaining an object from a resource + * pool (when the semaphore count indicates the number of resources available). + * + * @param xSemaphore A handle to the semaphore being taken. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully taken, otherwise + * pdFALSE + */ +#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) + /** * semphr. h *
xSemaphoreHandle xSemaphoreCreateMutex( void )
@@ -591,7 +633,7 @@ typedef xQueueHandle xSemaphoreHandle; * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex * \ingroup Semaphores */ -#define xSemaphoreCreateMutex() xQueueCreateMutex() +#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) /** @@ -646,7 +688,7 @@ typedef xQueueHandle xSemaphoreHandle; * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex * \ingroup Semaphores */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) /** * semphr. h @@ -711,6 +753,34 @@ typedef xQueueHandle xSemaphoreHandle; */ #define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) +/** + * semphr. h + *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \page vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) ( xSemaphore ) ) + +/** + * semphr.h + *
xTaskHandle xSemaphoreGetMutexHolder( xSemaphoreHandle xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + * Note: This Is is a good way of determining if the calling task is the mutex + * holder, but not a good way of determining the identity of the mutex holder as + * the holder may change between the function exiting and the returned value + * being tested. + */ +#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) #endif /* SEMAPHORE_H */ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h old mode 100644 new mode 100755 index 6c476ee00..e7a989d40 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -47,14 +41,28 @@ 1 tab == 4 spaces! - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - Selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ @@ -76,7 +84,7 @@ extern "C" { * MACROS AND DEFINITIONS *----------------------------------------------------------*/ -#define tskKERNEL_VERSION_NUMBER "V7.0.1" +#define tskKERNEL_VERSION_NUMBER "V7.2.0" /** * task. h @@ -1005,6 +1013,20 @@ portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; */ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; +/** + * task. h + *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQueury. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be + * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. + * + * \page pcTaskGetTaskName pcTaskGetTaskName + * \ingroup TaskUtils + */ +signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); + /** * task. h *
void vTaskList( char *pcWriteBuffer );
@@ -1063,40 +1085,6 @@ void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; */ void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; -/** - * task. h - *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
- * - * Starts a real time kernel activity trace. The trace logs the identity of - * which task is running when. - * - * The trace file is stored in binary format. A separate DOS utility called - * convtrce.exe is used to convert this into a tab delimited text file which - * can be viewed and plotted in a spread sheet. - * - * @param pcBuffer The buffer into which the trace will be written. - * - * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue - * until either the buffer in full, or ulTaskEndTrace () is called. - * - * \page vTaskStartTrace vTaskStartTrace - * \ingroup TaskUtils - */ -void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned long ulTaskEndTrace( void );
- * - * Stops a kernel activity trace. See vTaskStartTrace (). - * - * @return The number of bytes that have been written into the trace buffer. - * - * \page usTaskEndTrace usTaskEndTrace - * \ingroup TaskUtils - */ -unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; - /** * task.h *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
@@ -1117,19 +1105,6 @@ unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; */ unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
- * - * Returns the run time of selected task - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The run time of selected task - */ -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); - /* When using trace macros it is sometimes necessary to include tasks.h before FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, so the following two prototypes will cause a compilation error. This can be @@ -1170,6 +1145,14 @@ constant. */ */ portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTaskGetIdleTaskHandle( void ); /*----------------------------------------------------------- * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES @@ -1242,19 +1225,6 @@ void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickT */ signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 - * for this function to be available. - * See the configuration section for more information. - * - * Empties the ready and delayed queues of task control blocks, freeing the - * memory allocated for the task control block and task stacks as it goes. - */ -void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; - /* * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS @@ -1311,6 +1281,18 @@ void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUN */ signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; +/* + * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. + */ +unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ); + +/* + * Set the uxTCBNumber of the task referenced by the xTask parameter to + * ucHandle. + */ +void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ); + + #ifdef __cplusplus } #endif diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h old mode 100644 new mode 100755 index 3d78c0ae0..5f62368f5 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ @@ -67,6 +74,7 @@ #include "portable.h" #include "list.h" +#include "task.h" #ifdef __cplusplus extern "C" { @@ -97,7 +105,7 @@ typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); /** * xTimerHandle xTimerCreate( const signed char *pcTimerName, - * portTickType xTimerPeriod, + * portTickType xTimerPeriodInTicks, * unsigned portBASE_TYPE uxAutoReload, * void * pvTimerID, * tmrTIMER_CALLBACK pxCallbackFunction ); @@ -115,15 +123,15 @@ typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); * purely to assist debugging. The kernel itself only ever references a timer by * its handle, and never by its name. * - * @param xTimerPeriod The timer period. The time is defined in tick periods so + * @param xTimerPeriodInTicks The timer period. The time is defined in tick periods so * the constant portTICK_RATE_MS can be used to convert a time that has been * specified in milliseconds. For example, if the timer must expire after 100 - * ticks, then xTimerPeriod should be set to 100. Alternatively, if the timer + * ticks, then xTimerPeriodInTicks should be set to 100. Alternatively, if the timer * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) * provided configTICK_RATE_HZ is less than or equal to 1000. * * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will - * expire repeatedly with a frequency set by the xTimerPeriod parameter. If + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. If * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and * enter the dormant state after it expires. * @@ -134,7 +142,7 @@ typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); * * @param pxCallbackFunction The function to call when the timer expires. * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, - * which is "void vCallbackFunction( xTIMER *xTimer );". + * which is "void vCallbackFunction( xTimerHandle xTimer );". * * @return If the timer is successfully create then a handle to the newly * created timer is returned. If the timer cannot be created (because either @@ -143,7 +151,6 @@ typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); * * Example usage: * - * * #define NUM_TIMERS 5 * * // An array to hold handles to the created timers. @@ -156,7 +163,7 @@ typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); * // The callback function does nothing but count the number of times the * // associated timer expires, and stop the timer once the timer has expired * // 10 times. - * void vTimerCallback( xTIMER *pxTimer ) + * void vTimerCallback( xTimerHandle pxTimer ) * { * long lArrayIndex; * const long xMaxExpiryCountBeforeStopping = 10; @@ -283,6 +290,15 @@ void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; */ portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; +/** + * xTimerGetTimerDaemonTaskHandle() is only available if + * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); + /** * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); * @@ -551,7 +567,7 @@ portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; * * // The callback function assigned to the one-shot timer. In this case the * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) + * void vBacklightTimerCallback( xTimerHandle pxTimer ) * { * // The timer expired, therefore 5 seconds must have passed since a key * // was pressed. Switch off the LCD back-light. @@ -657,7 +673,7 @@ portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; * * // The callback function assigned to the one-shot timer. In this case the * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) + * void vBacklightTimerCallback( xTimerHandle pxTimer ) * { * // The timer expired, therefore 5 seconds must have passed since a key * // was pressed. Switch off the LCD back-light. @@ -876,7 +892,7 @@ portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; * * // The callback function assigned to the one-shot timer. In this case the * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) + * void vBacklightTimerCallback( xTimerHandle pxTimer ) * { * // The timer expired, therefore 5 seconds must have passed since a key * // was pressed. Switch off the LCD back-light. @@ -925,7 +941,7 @@ portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; * for use by the kernel only. */ portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; #ifdef __cplusplus } diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c old mode 100644 new mode 100755 index c3ef2a89d..9ae5d86e4 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c old mode 100644 new mode 100755 index 70c74912a..a02804ade --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c @@ -1,6 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + *************************************************************************** * * @@ -40,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ /*----------------------------------------------------------- @@ -104,7 +117,7 @@ void vPortSVCHandler( void ) __attribute__ (( naked )); /* * Start first task is a separate function so it can be tested in isolation. */ -void vPortStartFirstTask( void ) __attribute__ (( naked )); +static void prvPortStartFirstTask( void ) __attribute__ (( naked )); /*-----------------------------------------------------------*/ @@ -148,7 +161,7 @@ void vPortSVCHandler( void ) } /*-----------------------------------------------------------*/ -void vPortStartFirstTask( void ) +static void prvPortStartFirstTask( void ) { __asm volatile( " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ @@ -167,6 +180,10 @@ void vPortStartFirstTask( void ) */ portBASE_TYPE xPortStartScheduler( void ) { + /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. + See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ + configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); + /* Make PendSV, CallSV and SysTick the same priroity as the kernel. */ *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; @@ -179,7 +196,7 @@ portBASE_TYPE xPortStartScheduler( void ) uxCriticalNesting = 0; /* Start the first task. */ - vPortStartFirstTask(); + prvPortStartFirstTask(); /* Should not get here! */ return 0; diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h old mode 100644 new mode 100755 index c2860d1e9..80e2d67c5 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h @@ -1,5 +1,5 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. *************************************************************************** @@ -40,23 +40,34 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #ifndef PORTMACRO_H #define PORTMACRO_H -#include "stdint.h" - #ifdef __cplusplus extern "C" { #endif @@ -121,7 +132,8 @@ extern void vPortYieldFromISR( void ); /* * Set basepri back to 0 without effective other registers. - * r0 is clobbered. + * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see + * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. */ #define portCLEAR_INTERRUPT_MASK() \ __asm volatile \ @@ -131,6 +143,9 @@ extern void vPortYieldFromISR( void ); :::"r0" \ ) +/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a +bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before +disagreeing. */ #define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() #define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x @@ -138,9 +153,6 @@ extern void vPortYieldFromISR( void ); extern void vPortEnterCritical( void ); extern void vPortExitCritical( void ); -void PIOS_RTC_Init(); -uint32_t PIOS_RTC_Counter(); - #define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() #define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() #define portENTER_CRITICAL() vPortEnterCritical() diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c old mode 100644 new mode 100755 index 2ae7c7030..4748860db --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ #include @@ -67,7 +74,10 @@ task.h is included from an application file. */ #include "FreeRTOS.h" #include "task.h" -#include "croutine.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif #undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE @@ -75,7 +85,7 @@ task.h is included from an application file. */ * PUBLIC LIST API documented in list.h *----------------------------------------------------------*/ -/* Constants used with the cRxLock and cTxLock structure members. */ +/* Constants used with the cRxLock and xTxLock structure members. */ #define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) #define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) @@ -93,9 +103,16 @@ task.h is included from an application file. */ /* Semaphores do not actually store or copy data, so have an items size of zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0 ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0U ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) + +/* These definitions *must* match those in queue.h. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) /* * Definition of the queue used by the scheduler. @@ -116,8 +133,13 @@ typedef struct QueueDefinition unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned char ucQueueNumber; + unsigned char ucQueueType; + #endif } xQUEUE; /*-----------------------------------------------------------*/ @@ -134,14 +156,14 @@ typedef xQUEUE * xQueueHandle; * include the API header file (as it defines xQueueHandle differently). These * functions are documented in the API header file. */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) PRIVILEGED_FUNCTION; xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; @@ -151,6 +173,11 @@ signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRI signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) PRIVILEGED_FUNCTION; +xTaskHandle xQueueGetMutexHolder( xQueueHandle xSemaphore ) PRIVILEGED_FUNCTION; /* * Co-routine queue functions differ from task queue functions. Co-routines are @@ -249,12 +276,59 @@ static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) * PUBLIC QUEUE MANAGEMENT API documented in queue.h *----------------------------------------------------------*/ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) +{ + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); + pxQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxQueue->pcWriteTo = pxQueue->pcHead; + pxQueue->pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( unsigned portBASE_TYPE ) 1U ) * pxQueue->uxItemSize ); + pxQueue->xRxLock = queueUNLOCKED; + pxQueue->xTxLock = queueUNLOCKED; + + if( xNewQueue == pdFALSE ) + { + /* If there are tasks blocked waiting to read from the queue, then + the tasks will remain blocked as after this function exits the queue + will still be empty. If there are tasks blocked waiting to write to + the queue, then one should be unblocked as after this function exits + it will be possible to write to it. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + /* Ensure the event queues start in the correct state. */ + vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); + } + } + taskEXIT_CRITICAL(); + + /* A value is returned for calling semantic consistency with previous + versions. */ + return pdPASS; +} +/*-----------------------------------------------------------*/ + +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) { xQUEUE *pxNewQueue; size_t xQueueSizeInBytes; xQueueHandle xReturn = NULL; + /* Remove compiler warnings about unused parameters should + configUSE_TRACE_FACILITY not be set to 1. */ + ( void ) ucQueueType; + /* Allocate the new queue structure. */ if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) { @@ -270,25 +344,21 @@ xQueueHandle xReturn = NULL; { /* Initialise the queue members as described above where the queue type is defined. */ - pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->pcWriteTo = pxNewQueue->pcHead; - pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - ( unsigned portBASE_TYPE ) 1U ) * uxItemSize ); pxNewQueue->uxLength = uxQueueLength; pxNewQueue->uxItemSize = uxItemSize; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Likewise ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + xQueueGenericReset( pxNewQueue, pdTRUE ); + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif /* configUSE_TRACE_FACILITY */ traceQUEUE_CREATE( pxNewQueue ); xReturn = pxNewQueue; } else { - traceQUEUE_CREATE_FAILED(); + traceQUEUE_CREATE_FAILED( ucQueueType ); vPortFree( pxNewQueue ); } } @@ -302,10 +372,14 @@ xQueueHandle xReturn = NULL; #if ( configUSE_MUTEXES == 1 ) - xQueueHandle xQueueCreateMutex( void ) + xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) { xQUEUE *pxNewQueue; + /* Prevent compiler warnings about unused parameters if + configUSE_TRACE_FACILITY does not equal 1. */ + ( void ) ucQueueType; + /* Allocate the new queue structure. */ pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); if( pxNewQueue != NULL ) @@ -328,14 +402,20 @@ xQueueHandle xReturn = NULL; pxNewQueue->xRxLock = queueUNLOCKED; pxNewQueue->xTxLock = queueUNLOCKED; + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif + /* Ensure the event queues start with the correct state. */ vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + traceCREATE_MUTEX( pxNewQueue ); + /* Start with the semaphore in the expected state. */ xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); - - traceCREATE_MUTEX( pxNewQueue ); } else { @@ -349,7 +429,37 @@ xQueueHandle xReturn = NULL; #endif /* configUSE_MUTEXES */ /*-----------------------------------------------------------*/ -#if configUSE_RECURSIVE_MUTEXES == 1 +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xQueueGetMutexHolder == 1 ) ) + + void* xQueueGetMutexHolder( xQueueHandle xSemaphore ) + { + void *pxReturn; + + /* This function is called by xSemaphoreGetMutexHolder(), and should not + be called directly. Note: This is is a good way of determining if the + calling task is the mutex holder, but not a good way of determining the + identity of the mutex holder, as the holder may change between the + following critical section exiting and the function returning. */ + taskENTER_CRITICAL(); + { + if( xSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = ( void * ) xSemaphore->pxMutexHolder; + } + else + { + pxReturn = NULL; + } + } + taskEXIT_CRITICAL(); + + return pxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) { @@ -444,7 +554,7 @@ xQueueHandle xReturn = NULL; { xQueueHandle pxHandle; - pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); + pxHandle = xQueueGenericCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); if( pxHandle != NULL ) { @@ -539,7 +649,7 @@ xTimeOutType xTimeOut; /* Update the timeout state to see if it has expired yet. */ if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) { - if( prvIsQueueFull( pxQueue ) ) + if( prvIsQueueFull( pxQueue ) != pdFALSE ) { traceBLOCKING_ON_QUEUE_SEND( pxQueue ); vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); @@ -556,7 +666,7 @@ xTimeOutType xTimeOut; task is already in a ready list before it yields - in which case the yield will not cause a context switch unless there is also a higher priority task in the pending ready list. */ - if( !xTaskResumeAll() ) + if( xTaskResumeAll() == pdFALSE ) { portYIELD_WITHIN_API(); } @@ -639,7 +749,7 @@ xTimeOutType xTimeOut; { if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) { - if( prvIsQueueFull( pxQueue ) ) + if( prvIsQueueFull( pxQueue ) != pdFALSE ) { traceBLOCKING_ON_QUEUE_SEND( pxQueue ); vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); @@ -755,7 +865,7 @@ xTimeOutType xTimeOut; { if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) { - if( prvIsQueueEmpty( pxQueue ) ) + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) { traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); @@ -795,7 +905,6 @@ signed portBASE_TYPE xReturn; unsigned portBASE_TYPE uxSavedInterruptStatus; configASSERT( pxQueue ); - configASSERT( pxHigherPriorityTaskWoken ); configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); /* Similar to xQueueGenericSend, except we don't block if there is no room @@ -821,7 +930,10 @@ unsigned portBASE_TYPE uxSavedInterruptStatus; { /* The task waiting has a higher priority so record that a context switch is required. */ - *pxHigherPriorityTaskWoken = pdTRUE; + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } } } } @@ -918,7 +1030,6 @@ signed char *pcOriginalReadPosition; portYIELD_WITHIN_API(); } } - } taskEXIT_CRITICAL(); @@ -954,7 +1065,7 @@ signed char *pcOriginalReadPosition; /* Update the timeout state to see if it has expired yet. */ if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) { - if( prvIsQueueEmpty( pxQueue ) ) + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) { traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); @@ -973,7 +1084,7 @@ signed char *pcOriginalReadPosition; vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); prvUnlockQueue( pxQueue ); - if( !xTaskResumeAll() ) + if( xTaskResumeAll() == pdFALSE ) { portYIELD_WITHIN_API(); } @@ -996,13 +1107,12 @@ signed char *pcOriginalReadPosition; } /*-----------------------------------------------------------*/ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) { signed portBASE_TYPE xReturn; unsigned portBASE_TYPE uxSavedInterruptStatus; configASSERT( pxQueue ); - configASSERT( pxTaskWoken ); configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); @@ -1026,7 +1136,10 @@ unsigned portBASE_TYPE uxSavedInterruptStatus; { /* The task waiting has a higher priority than us so force a context switch. */ - *pxTaskWoken = pdTRUE; + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } } } } @@ -1088,6 +1201,36 @@ void vQueueDelete( xQueueHandle pxQueue ) } /*-----------------------------------------------------------*/ +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) + { + pxQueue->ucQueueNumber = ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueType; + } + +#endif +/*-----------------------------------------------------------*/ + static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) { if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) @@ -1260,7 +1403,7 @@ signed portBASE_TYPE xReturn; between the check to see if the queue is full and blocking on the queue. */ portDISABLE_INTERRUPTS(); { - if( prvIsQueueFull( pxQueue ) ) + if( prvIsQueueFull( pxQueue ) != pdFALSE ) { /* The queue is full - do we want to block or just leave without posting? */ @@ -1404,7 +1547,7 @@ signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvIt /* We only want to wake one co-routine per ISR, so check that a co-routine has not already been woken. */ - if( !xCoRoutinePreviouslyWoken ) + if( xCoRoutinePreviouslyWoken == pdFALSE ) { if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) { @@ -1439,7 +1582,7 @@ signed portBASE_TYPE xReturn; --( pxQueue->uxMessagesWaiting ); memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - if( !( *pxCoRoutineWoken ) ) + if( ( *pxCoRoutineWoken ) == pdFALSE ) { if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) { @@ -1470,7 +1613,7 @@ signed portBASE_TYPE xReturn; /* See if there is an empty space in the registry. A NULL name denotes a free slot. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) { if( xQueueRegistry[ ux ].pcQueueName == NULL ) { @@ -1493,7 +1636,7 @@ signed portBASE_TYPE xReturn; /* See if the handle of the queue being unregistered in actually in the registry. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) { if( xQueueRegistry[ ux ].xHandle == xQueue ) { diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c old mode 100644 new mode 100755 index 865d5e9db..0c43e63d6 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c @@ -1,11 +1,5 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. *************************************************************************** @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ @@ -106,7 +113,8 @@ typedef struct tskTaskControlBlock #endif #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ + unsigned portBASE_TYPE uxTCBNumber; /*< This stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ + unsigned portBASE_TYPE uxTaskNumber; /*< This stores a number specifically for use by third party trace code. */ #endif #if ( configUSE_MUTEXES == 1 ) @@ -146,8 +154,8 @@ PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been r #if ( INCLUDE_vTaskDelete == 1 ) - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; + PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; #endif @@ -157,17 +165,23 @@ PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been r #endif +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; + +#endif + /* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; #if ( configGENERATE_RUN_TIME_STATS == 1 ) @@ -194,58 +208,6 @@ PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) #define tskDELETED_CHAR ( ( signed char ) 'D' ) #define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255U; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif /*-----------------------------------------------------------*/ /* @@ -256,6 +218,7 @@ PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) * executing task has been rescheduled. */ #define prvAddTaskToReadyQueue( pxTCB ) \ + traceMOVED_TASK_TO_READY_STATE( pxTCB ) \ if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ { \ uxTopReadyPriority = ( pxTCB )->uxPriority; \ @@ -313,7 +276,7 @@ portTickType xItemValue; \ vListRemove( &( pxTCB->xGenericListItem ) ); \ \ /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ + if( pxTCB->xEventListItem.pvContainer != NULL ) \ { \ vListRemove( &( pxTCB->xEventListItem ) ); \ } \ @@ -333,7 +296,7 @@ portTickType xItemValue; \ #define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) /* Callback function prototypes. --------------------------*/ -extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); +extern void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName ); extern void vApplicationTickHook( void ); /* File private functions. --------------------------------*/ @@ -370,7 +333,7 @@ static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); * This does not free memory allocated by the task itself (i.e. memory * allocated by calls to pvPortMalloc from within the tasks application code). */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) +#if ( INCLUDE_vTaskDelete == 1 ) static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; @@ -436,7 +399,7 @@ signed portBASE_TYPE xReturn; tskTCB * pxNewTCB; configASSERT( pxTaskCode ); - configASSERT( ( uxPriority < configMAX_PRIORITIES ) ); + configASSERT( ( ( uxPriority & ( ~portPRIVILEGE_BIT ) ) < configMAX_PRIORITIES ) ); /* Allocate the memory required by the TCB and stack for the new task, checking that the allocation was successful. */ @@ -449,7 +412,7 @@ tskTCB * pxNewTCB; #if( portUSING_MPU_WRAPPERS == 1 ) /* Should the task be created in privileged mode? */ portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) { xRunPrivileged = pdTRUE; } @@ -467,7 +430,7 @@ tskTCB * pxNewTCB; #if( portSTACK_GROWTH < 0 ) { pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); /* Check the alignment of the calculated top of stack is correct. */ configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); @@ -504,7 +467,7 @@ tskTCB * pxNewTCB; #endif /* Check the alignment of the initialised stack. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + portALIGNMENT_ASSERT_pxCurrentTCB( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); if( ( void * ) pxCreatedTask != NULL ) { @@ -565,6 +528,7 @@ tskTCB * pxNewTCB; prvAddTaskToReadyQueue( pxNewTCB ); xReturn = pdPASS; + portSETUP_TCB( pxNewTCB ); traceTASK_CREATE( pxNewTCB ); } taskEXIT_CRITICAL(); @@ -617,7 +581,7 @@ tskTCB * pxNewTCB; vListRemove( &( pxTCB->xGenericListItem ) ); /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) + if( pxTCB->xEventListItem.pvContainer != NULL ) { vListRemove( &( pxTCB->xEventListItem ) ); } @@ -666,7 +630,7 @@ tskTCB * pxNewTCB; portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; configASSERT( pxPreviousWakeTime ); - configASSERT( ( xTimeIncrement > 0 ) ); + configASSERT( ( xTimeIncrement > 0U ) ); vTaskSuspendAll(); { @@ -714,7 +678,7 @@ tskTCB * pxNewTCB; /* Force a reschedule if xTaskResumeAll has not already done so, we may have put ourselves to sleep. */ - if( !xAlreadyYielded ) + if( xAlreadyYielded == pdFALSE ) { portYIELD_WITHIN_API(); } @@ -731,7 +695,7 @@ tskTCB * pxNewTCB; signed portBASE_TYPE xAlreadyYielded = pdFALSE; /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) + if( xTicksToDelay > ( portTickType ) 0U ) { vTaskSuspendAll(); { @@ -760,7 +724,7 @@ tskTCB * pxNewTCB; /* Force a reschedule if xTaskResumeAll has not already done so, we may have put ourselves to sleep. */ - if( !xAlreadyYielded ) + if( xAlreadyYielded == pdFALSE ) { portYIELD_WITHIN_API(); } @@ -818,7 +782,7 @@ tskTCB * pxNewTCB; priority of the calling function. */ pxTCB = prvGetTCBFromHandle( pxTask ); - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); + traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); #if ( configUSE_MUTEXES == 1 ) { @@ -923,7 +887,7 @@ tskTCB * pxNewTCB; vListRemove( &( pxTCB->xGenericListItem ) ); /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) + if( pxTCB->xEventListItem.pvContainer != NULL ) { vListRemove( &( pxTCB->xEventListItem ) ); } @@ -944,7 +908,7 @@ tskTCB * pxNewTCB; /* The scheduler is not running, but the task that was pointed to by pxCurrentTCB has just been suspended and pxCurrentTCB must be adjusted to point to a different task. */ - if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) { /* No other tasks are ready, so set pxCurrentTCB back to NULL so when the next task is created pxCurrentTCB will @@ -1048,29 +1012,34 @@ tskTCB * pxNewTCB; { portBASE_TYPE xYieldRequired = pdFALSE; tskTCB *pxTCB; + unsigned portBASE_TYPE uxSavedInterruptStatus; configASSERT( pxTaskToResume ); pxTCB = ( tskTCB * ) pxTaskToResume; - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); { - traceTASK_RESUME_FROM_ISR( pxTCB ); + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } } } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); return xYieldRequired; } @@ -1090,7 +1059,18 @@ void vTaskStartScheduler( void ) portBASE_TYPE xReturn; /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); + #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + { + /* Create the idle task, storing its handle in xIdleTaskHandle so it can + be returned by the xTaskGetIdleTaskHandle() function. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); + } + #else + { + /* Create the idle task without storing its handle. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); + } + #endif #if ( configUSE_TIMERS == 1 ) { @@ -1114,7 +1094,7 @@ portBASE_TYPE xReturn; portDISABLE_INTERRUPTS(); xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; + xTickCount = ( portTickType ) 0U; /* If configGENERATE_RUN_TIME_STATS is defined then the following macro must be defined to configure the timer/counter used to generate @@ -1123,7 +1103,7 @@ portBASE_TYPE xReturn; /* Setting up the timer tick is hardware specific and thus in the portable interface. */ - if( xPortStartScheduler() ) + if( xPortStartScheduler() != pdFALSE ) { /* Should not reach here as if the scheduler is running the function will not return. */ @@ -1178,7 +1158,7 @@ signed portBASE_TYPE xAlreadyYielded = pdFALSE; if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) { portBASE_TYPE xYieldRequired = pdFALSE; @@ -1202,9 +1182,9 @@ signed portBASE_TYPE xAlreadyYielded = pdFALSE; /* If any ticks occurred while the scheduler was suspended then they should be processed now. This ensures the tick count does not slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) { vTaskIncrementTick(); --uxMissedTicks; @@ -1281,6 +1261,21 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) } /*-----------------------------------------------------------*/ +#if ( INCLUDE_pcTaskGetTaskName == 1 ) + + signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) + { + tskTCB *pxTCB; + + /* If null is passed in here then the name of the calling task is being queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); + } + +#endif +/*-----------------------------------------------------------*/ + #if ( configUSE_TRACE_FACILITY == 1 ) void vTaskList( signed char *pcWriteBuffer ) @@ -1324,7 +1319,7 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) { if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); + prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); } } #endif @@ -1333,7 +1328,7 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) { if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); + prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); } } #endif @@ -1399,7 +1394,7 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) { if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); } } #endif @@ -1408,7 +1403,7 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) { if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); } } #endif @@ -1419,51 +1414,23 @@ unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) #endif /*----------------------------------------------------------*/ -#if ( configUSE_TRACE_FACILITY == 1 ) +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) + xTaskHandle xTaskGetIdleTaskHandle( void ) { - configASSERT( pcBuffer ); - configASSERT( ulBufferSize ); - - taskENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - taskEXIT_CRITICAL(); + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; } - + #endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - taskENTER_CRITICAL(); - xTracing = pdFALSE; - taskEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - /*----------------------------------------------------------- * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES * documented in task.h *----------------------------------------------------------*/ - void vTaskIncrementTick( void ) { tskTCB * pxTCB; @@ -1474,7 +1441,7 @@ tskTCB * pxTCB; if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) { ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) + if( xTickCount == ( portTickType ) 0U ) { xList *pxTemp; @@ -1490,18 +1457,18 @@ tskTCB * pxTCB; if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) { - /* The new current delayed list is empty. Set - xNextTaskUnblockTime to the maximum possible value so it is + /* The new current delayed list is empty. Set + xNextTaskUnblockTime to the maximum possible value so it is extremely unlikely that the - if( xTickCount >= xNextTaskUnblockTime ) test will pass until + if( xTickCount >= xNextTaskUnblockTime ) test will pass until there is an item in the delayed list. */ xNextTaskUnblockTime = portMAX_DELAY; } else { - /* The new current delayed list is not empty, get the value of - the item at the head of the delayed list. This is the time at - which the task at the head of the delayed list should be removed + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed from the Blocked state. */ pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); @@ -1539,59 +1506,6 @@ tskTCB * pxTCB; } /*-----------------------------------------------------------*/ -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( listLIST_IS_EMPTY( &xDelayedTaskList1 ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( listLIST_IS_EMPTY( &xDelayedTaskList2 ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) @@ -1726,7 +1640,6 @@ void vTaskSwitchContext( void ) listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); } } /*-----------------------------------------------------------*/ @@ -1922,6 +1835,42 @@ void vTaskMissedYield( void ) { xMissedYield = pdTRUE; } +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ) + { + unsigned portBASE_TYPE uxReturn; + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + uxReturn = pxTCB->uxTaskNumber; + } + else + { + uxReturn = 0U; + } + + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ) + { + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + pxTCB->uxTaskNumber = uxHandle; + } + } +#endif + /* * ----------------------------------------------------------- @@ -2037,7 +1986,7 @@ static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const #if ( portCRITICAL_NESTING_IN_TCB == 1 ) { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; } #endif @@ -2125,7 +2074,7 @@ static void prvCheckTasksWaitingTermination( void ) /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) { vTaskSuspendAll(); xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); @@ -2202,7 +2151,7 @@ tskTCB *pxNewTCB; else { /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); + memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); } } @@ -2216,6 +2165,7 @@ tskTCB *pxNewTCB; { volatile tskTCB *pxNextTCB, *pxFirstTCB; unsigned short usStackRemaining; + PRIVILEGED_DATA static char pcStatusString[ configMAX_TASK_NAME_LEN + 30 ]; /* Write the details of all the TCB's in pxList into the buffer. */ listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); @@ -2259,7 +2209,7 @@ tskTCB *pxNewTCB; if( ulTotalRunTime > 0UL ) { /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) + if( pxNextTCB->ulRunTimeCounter == 0UL ) { /* The task has used no CPU time at all. */ sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); @@ -2312,26 +2262,11 @@ tskTCB *pxNewTCB; #endif /*-----------------------------------------------------------*/ -#if ( INCLUDE_uxTaskGetRunTime == 1 ) -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) -{ - unsigned long runTime; - - tskTCB *pxTCB; - pxTCB = prvGetTCBFromHandle( xTask ); - runTime = pxTCB->ulRunTimeCounter; - pxTCB->ulRunTimeCounter = 0; - return runTime; -} - -#endif -/*-----------------------------------------------------------*/ - #if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) { - register unsigned short usCount = 0; + register unsigned short usCount = 0U; while( *pucStackByte == tskSTACK_FILL_BYTE ) { @@ -2375,10 +2310,15 @@ unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) #endif /*-----------------------------------------------------------*/ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) +#if ( INCLUDE_vTaskDelete == 1 ) static void prvDeleteTCB( tskTCB *pxTCB ) { + /* This call is required specifically for the TriCore port. It must be + above the vPortFree() calls. The call is also used by ports/demos that + want to allocate and clean RAM statically. */ + portCLEAN_UP_TCB( pxTCB ); + /* Free up the memory allocated by the scheduler for the task. It is up to the task to free any memory allocated at the application level. */ vPortFreeAligned( pxTCB->pxStack ); @@ -2451,7 +2391,7 @@ unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) /* If the task being modified is in the ready state it will need to be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) { vListRemove( &( pxTCB->xGenericListItem ) ); @@ -2464,6 +2404,8 @@ unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) /* Just inherit the priority. */ pxTCB->uxPriority = pxCurrentTCB->uxPriority; } + + traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority ); } } @@ -2484,8 +2426,9 @@ unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) Remove ourselves from the ready list we currently appear in. */ vListRemove( &( pxTCB->xGenericListItem ) ); - /* Disinherit the priority before adding ourselves into the new + /* Disinherit the priority before adding the task into the new ready list. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); pxTCB->uxPriority = pxTCB->uxBasePriority; listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); prvAddTaskToReadyQueue( pxTCB ); @@ -2517,11 +2460,11 @@ void vTaskExitCritical( void ) { if( xSchedulerRunning != pdFALSE ) { - if( pxCurrentTCB->uxCriticalNesting > 0 ) + if( pxCurrentTCB->uxCriticalNesting > 0U ) { ( pxCurrentTCB->uxCriticalNesting )--; - if( pxCurrentTCB->uxCriticalNesting == 0 ) + if( pxCurrentTCB->uxCriticalNesting == 0U ) { portENABLE_INTERRUPTS(); } diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c old mode 100644 new mode 100755 index 7e5ef22ad..0be294277 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c @@ -1,12 +1,6 @@ /* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - *************************************************************************** * * @@ -46,15 +40,28 @@ FreeRTOS WEB site. 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. */ /* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining @@ -110,6 +117,12 @@ PRIVILEGED_DATA static xList *pxOverflowTimerList; /* A queue that is used to send commands to the timer service task. */ PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; + +#endif + /*-----------------------------------------------------------*/ /* @@ -183,7 +196,18 @@ portBASE_TYPE xReturn = pdFAIL; if( xTimerQueue != NULL ) { - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, NULL); + #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + { + /* Create the timer task, storing its handle in xTimerTaskHandle so + it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle ); + } + #else + { + /* Create the timer task without storing its handle. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL); + } + #endif } configASSERT( xReturn ); @@ -230,7 +254,7 @@ xTIMER *pxNewTimer; } /*-----------------------------------------------------------*/ -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) { portBASE_TYPE xReturn = pdFAIL; xTIMER_MESSAGE xMessage; @@ -267,6 +291,19 @@ xTIMER_MESSAGE xMessage; } /*-----------------------------------------------------------*/ +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) + { + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; + } + +#endif +/*-----------------------------------------------------------*/ + static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) { xTIMER *pxTimer; @@ -405,7 +442,7 @@ portTickType xNextExpireTime; static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) { portTickType xTimeNow; -static portTickType xLastTime = ( portTickType ) 0U; +PRIVILEGED_DATA static portTickType xLastTime = ( portTickType ) 0U; xTimeNow = xTaskGetTickCount(); diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c deleted file mode 100644 index a235531d1..000000000 --- a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/port.c +++ /dev/null @@ -1,364 +0,0 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the ARM Cortex-M4F port. - *----------------------------------------------------------*/ - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" - -/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is -defined. The value should also ensure backward compatibility. -FreeRTOS.org versions prior to V4.4.0 did not include this definition. */ -#ifndef configKERNEL_INTERRUPT_PRIORITY - #define configKERNEL_INTERRUPT_PRIORITY 255 -#endif - -/* Constants required to manipulate the NVIC. */ -#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long *) 0xe000e010 ) -#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long *) 0xe000e014 ) -#define portNVIC_INT_CTRL ( ( volatile unsigned long *) 0xe000ed04 ) -#define portNVIC_SYSPRI2 ( ( volatile unsigned long *) 0xe000ed20 ) -#define portNVIC_SYSTICK_CLK 0x00000004 -#define portNVIC_SYSTICK_INT 0x00000002 -#define portNVIC_SYSTICK_ENABLE 0x00000001 -#define portNVIC_PENDSVSET 0x10000000 -#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) -#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) - -/* Constants required to set up the initial stack. */ -#define portINITIAL_XPSR ( 0x01000000 ) -#define portINITIAL_EXC_RETURN ( 0xfffffffd ) /* return to thread mode, basic stack frame, FPU not used */ - -/* The priority used by the kernel is assigned to a variable to make access -from inline assembler easier. */ -const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; - -/* Each task maintains its own interrupt status in the critical nesting -variable. */ -static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); - -/* - * Exception handlers. - */ -void xPortPendSVHandler( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); -void xPortSysTickHandler( void ) __attribute__((no_instrument_function)); -void vPortSVCHandler( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -void vPortStartFirstTask( void ) __attribute__ (( naked )) __attribute__((no_instrument_function)); - -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, portSTACK_TYPE *pxStartOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ - /* - * Create a basic stack frame plus manual save area as would be - * saved by xPortPendSVHandler on entry, for a task that has not - * used the FPU. - * - * XXX if pxTopOfStack is not 8-byte aligned and the CPU is configured - * to adjust the stack to 8-byte boundaries, is this code safe? - */ - - /* automatically stacked state */ - *--pxTopOfStack = portINITIAL_XPSR; /* xPSR */ - *--pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* pc (thread entrypoint) */ - *--pxTopOfStack = 0; /* lr */ - *--pxTopOfStack = 0; /* r12 */ - *--pxTopOfStack = 0; /* r3 */ - *--pxTopOfStack = 0; /* r2 */ - *--pxTopOfStack = 0; /* r1 */ - *--pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* r0 (void * passed to thread) */ - - /* manually stacked state */ - *--pxTopOfStack = 0; /* r11 */ - *--pxTopOfStack = ( portSTACK_TYPE ) pxStartOfStack;/* r10 (stack limit) */ - *--pxTopOfStack = 0; /* r9 */ - *--pxTopOfStack = 0; /* r8 */ - *--pxTopOfStack = 0; /* r7 */ - *--pxTopOfStack = 0; /* r6 */ - *--pxTopOfStack = 0; /* r5 */ - *--pxTopOfStack = 0; /* r4 */ - - /* exception return code */ - *--pxTopOfStack = portINITIAL_EXC_RETURN; - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortSVCHandler( void ) -{ - /* - * Start the first task. - */ - __asm volatile ( - " b context_restore \n" /* jump directly to the context restore path in xPortPendSVHandler */ - ); -} -/*-----------------------------------------------------------*/ - -void vPortStartFirstTask( void ) -{ - __asm volatile( - " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ - " ldr r0, [r0] \n" - " ldr r0, [r0] \n" - " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ - " cpsie i \n" /* Globally enable interrupts. */ - " svc 0 \n" /* System call to start first task. */ - " nop \n" - ); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ - /* Make PendSV, CallSV and SysTick the same priroity as the kernel. */ - *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; - *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - vPortStartFirstTask(); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ - /* It is unlikely that the CM3 port will require this function as there - is nothing to return to. */ -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Set a PendSV to request a context switch. */ - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - portDISABLE_INTERRUPTS(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - uxCriticalNesting--; - if( uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } -} -/*-----------------------------------------------------------*/ - -void xPortPendSVHandler( void ) -{ - /* This is a naked function. */ - /* - * XXX todo - check r0 against r10 for stack overflow detection? - */ - - /* - * Handle a PendSV exception, triggered by vPortYieldFromISR (etc). - * - * FP state saving is conditional on bit 4 of the EXC_RETURN value (lr). - * If the bit is 1, the frame saved by entry is a basic frame and FP - * state should not be saved. If the bit is 0, the frame saved is - * an extended frame and the high FP registers also need to be saved. - * - * Since the EXC_RETURN value is specific to the task, it is the last - * item stacked and the first to be popped when restoring a task's - * context. - */ - __asm volatile - ( - " mrs r0, psp \n" /* get the program stack pointer (base of automatic frame) in r0 */ - " \n" - " tst lr, 0x10 \n" /* check for extended stack frame */ - " bne 1f \n" /* skip FP register save if only a basic frame */ - " vstmdb r0!, {s16-s31} \n" /* stack the remaining FP registers */ - "1: \n" - " stmdb r0!, {r4-r11} \n" /* stack the remaining GP registers */ - " stmdb r0!, {lr} \n" /* stack the exception return code for use when resuming */ - " \n" - " ldr r3, 3f \n" /* pointer to pointer to current TCB in r3 */ - " ldr r2, [r3] \n" /* pointer to current TCB in r2 */ - " str r0, [r2] \n" /* save stack (context) pointer in the first member of the TCB */ - " \n" - " mov r0, %0 \n" /* switch to syscall interrupt priority */ - " msr basepri, r0 \n" - " \n" - " bl vTaskSwitchContext \n" /* handle the context switch call */ - " \n" - "context_restore: \n" /* branch target for vPortSVCHandler */ - " mov r0, #0 \n" /* reset to priority 0 */ - " msr basepri, r0 \n" - " \n" - " ldr r3, 3f \n" /* pointer to pointer to current TCB in r3 */ - " ldr r2, [r3] \n" /* pointer to current TCB in r2 */ - " ldr r0, [r2] \n" /* restore stack (context) pointer from the first member of the TCB */ - " \n" - " ldmia r0!, {lr} \n" /* pop the exception return code */ - " ldmia r0!, {r4-r11} \n" /* pop the manually-stacked GP registers */ - " tst lr, 0x10 \n" /* check for extended stack frame */ - " bne 2f \n" /* skip FP register pop if only a basic frame */ - " vldmia r0!, {s16-s31} \n" /* pop the manually-stacked FP registers */ - "2: \n" - " msr psp, r0 \n" /* reload the program stack pointer */ - " bx lr \n" /* perform an exception return as per the encoding in lr */ - " \n" - " .align 2 \n" - "3: .word pxCurrentTCB \n" - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) - ); -} -/*-----------------------------------------------------------*/ - -void xPortSysTickHandler( void ) -{ -unsigned long ulDummy; - - /* If using preemption, also force a context switch. */ - #if configUSE_PREEMPTION == 1 - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; - #endif - - ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); - { - vTaskIncrementTick(); - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ - /* Configure SysTick to interrupt at the requested rate. */ - *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; - *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; -} -/*-----------------------------------------------------------*/ - -void __cyg_profile_func_enter(void *func, void *caller) __attribute__((naked, no_instrument_function)); -void __cyg_profile_func_exit(void *func, void *caller) __attribute__((naked, no_instrument_function)); -void __stack_overflow_trap(void) __attribute__((naked, no_instrument_function)); - -void -__stack_trap(void) -{ - /* if we get here, the stack has overflowed */ - asm ( "b ."); -} - -void -__cyg_profile_func_enter(void *func, void *caller) -{ - asm volatile ( - " mrs r2, ipsr \n" /* Check whether we are in interrupt mode */ - " cmp r2, #0 \n" /* since we don't switch r10 on interrupt entry, we */ - " bne 2f \n" /* can't detect overflow of the interrupt stack. */ - " \n" - " sub r2, sp, #68 \n" /* compute stack pointer as though we just stacked a full frame */ - " mrs r1, control \n" /* Test CONTROL.FPCA to see whether we also need room for the FP */ - " tst r1, #4 \n" /* context. */ - " beq 1f \n" - " sub r2, r2, #136 \n" /* subtract FP context frame size */ - "1: \n" - " cmp r2, r10 \n" /* compare stack with limit */ - " bgt 2f \n" /* stack is above limit and thus OK */ - " b __stack_trap \n" - "2: \n" - " bx lr \n" - ); -} - -void -__cyg_profile_func_exit(void *func, void *caller) -{ - asm volatile("bx lr"); -} - - diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c new file mode 100755 index 000000000..c2c143fe2 --- /dev/null +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c @@ -0,0 +1,350 @@ +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/*----------------------------------------------------------- + * Implementation of functions defined in portable.h for the ARM CM4F port. + *----------------------------------------------------------*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +#ifndef __VFP_FP__ + #error This port can only be used when the project options are configured to enable hardware floating point support. +#endif + +/* Constants required to manipulate the NVIC. */ +#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long * ) 0xe000e010 ) +#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long * ) 0xe000e014 ) +#define portNVIC_INT_CTRL ( ( volatile unsigned long * ) 0xe000ed04 ) +#define portNVIC_SYSPRI2 ( ( volatile unsigned long * ) 0xe000ed20 ) +#define portNVIC_SYSTICK_CLK 0x00000004 +#define portNVIC_SYSTICK_INT 0x00000002 +#define portNVIC_SYSTICK_ENABLE 0x00000001 +#define portNVIC_PENDSVSET 0x10000000 +#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) +#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) + +/* Constants required to manipulate the VFP. */ +#define portFPCCR ( ( volatile unsigned long * ) 0xe000ef34 ) /* Floating point context control register. */ +#define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL ) + +/* Constants required to set up the initial stack. */ +#define portINITIAL_XPSR ( 0x01000000 ) +#define portINITIAL_EXEC_RETURN ( 0xfffffffd ) + +/* The priority used by the kernel is assigned to a variable to make access +from inline assembler easier. */ +const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; + +/* Each task maintains its own interrupt status in the critical nesting +variable. */ +static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; + +/* + * Setup the timer to generate the tick interrupts. + */ +static void prvSetupTimerInterrupt( void ); + +/* + * Exception handlers. + */ +void xPortPendSVHandler( void ) __attribute__ (( naked )); +void xPortSysTickHandler( void ); +void vPortSVCHandler( void ) __attribute__ (( naked )); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +static void vPortStartFirstTask( void ) __attribute__ (( naked )); + +/* + * Function to enable the VFP. + */ + static void vPortEnableVFP( void ) __attribute__ (( naked )); + + +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) +{ + /* Simulate the stack frame as it would be created by a context switch + interrupt. */ + + /* Offset added to account for the way the MCU uses the stack on entry/exit + of interrupts, and to ensure alignment. */ + pxTopOfStack--; + + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */ + pxTopOfStack--; + *pxTopOfStack = 0; /* LR */ + + /* Save code space by skipping register initialisation. */ + pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ + *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */ + + /* A save method is being used that requires each task to maintain its + own exec return value. */ + pxTopOfStack--; + *pxTopOfStack = portINITIAL_EXEC_RETURN; + + pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler( void ) +{ + __asm volatile ( + " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ + " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ + " msr psp, r0 \n" /* Restore the task stack pointer. */ + " mov r0, #0 \n" + " msr basepri, r0 \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst2: .word pxCurrentTCB \n" + ); +} +/*-----------------------------------------------------------*/ + +static void vPortStartFirstTask( void ) +{ + __asm volatile( + " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" + " ldr r0, [r0] \n" + " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ + " cpsie i \n" /* Globally enable interrupts. */ + " svc 0 \n" /* System call to start first task. */ + " nop \n" + ); +} +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portBASE_TYPE xPortStartScheduler( void ) +{ + /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. + See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ + configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); + + /* Make PendSV and SysTick the lowest priority interrupts. */ + *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; + *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; + + /* Start the timer that generates the tick ISR. Interrupts are disabled + here already. */ + prvSetupTimerInterrupt(); + + /* Initialise the critical nesting count ready for the first task. */ + uxCriticalNesting = 0; + + /* Ensure the VFP is enabled - it should be anyway. */ + vPortEnableVFP(); + + /* Lazy save always. */ + *( portFPCCR ) |= portASPEN_AND_LSPEN_BITS; + + /* Start the first task. */ + vPortStartFirstTask(); + + /* Should not get here! */ + return 0; +} +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) +{ + /* It is unlikely that the CM4F port will require this function as there + is nothing to return to. */ +} +/*-----------------------------------------------------------*/ + +void vPortYieldFromISR( void ) +{ + /* Set a PendSV to request a context switch. */ + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) +{ + portDISABLE_INTERRUPTS(); + uxCriticalNesting++; +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) +{ + uxCriticalNesting--; + if( uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void xPortPendSVHandler( void ) +{ + /* This is a naked function. */ + + __asm volatile + ( + " mrs r0, psp \n" + " \n" + " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ + " ldr r2, [r3] \n" + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */ + " it eq \n" + " vstmdbeq r0!, {s16-s31} \n" + " \n" + " stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */ + " \n" + " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ + " \n" + " stmdb sp!, {r3, r14} \n" + " mov r0, %0 \n" + " msr basepri, r0 \n" + " bl vTaskSwitchContext \n" + " mov r0, #0 \n" + " msr basepri, r0 \n" + " ldmia sp!, {r3, r14} \n" + " \n" + " ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldr r0, [r1] \n" + " \n" + " ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */ + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */ + " it eq \n" + " vldmiaeq r0!, {s16-s31} \n" + " \n" + " msr psp, r0 \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst: .word pxCurrentTCB \n" + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) + ); +} +/*-----------------------------------------------------------*/ + +void xPortSysTickHandler( void ) +{ +unsigned long ulDummy; + + /* If using preemption, also force a context switch. */ + #if configUSE_PREEMPTION == 1 + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; + #endif + + ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); + { + vTaskIncrementTick(); + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); +} +/*-----------------------------------------------------------*/ + +/* + * Setup the systick timer to generate the tick interrupts at the required + * frequency. + */ +void prvSetupTimerInterrupt( void ) +{ + /* Configure SysTick to interrupt at the requested rate. */ + *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; +} +/*-----------------------------------------------------------*/ + +/* This is a naked function. */ +static void vPortEnableVFP( void ) +{ + __asm volatile + ( + " ldr.w r0, =0xE000ED88 \n" /* The FPU enable bits are in the CPACR. */ + " ldr r1, [r0] \n" + " \n" + " orr r1, r1, #( 0xf << 20 ) \n" /* Enable CP10 and CP11 coprocessors, then save back. */ + " str r1, [r0] \n" + " bx r14 " + ); +} + diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h old mode 100644 new mode 100755 similarity index 72% rename from flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h rename to flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h index f346841af..798be5e09 --- a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4/portmacro.h +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h @@ -1,156 +1,178 @@ -/* - FreeRTOS V7.0.2 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG long -#define portSHORT short -#define portSTACK_TYPE unsigned portLONG -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Architecture specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 8 -/*-----------------------------------------------------------*/ - - -/* Scheduler utilities. */ -extern void vPortYieldFromISR( void ); - -#define portYIELD() vPortYieldFromISR() - -#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() -/*-----------------------------------------------------------*/ - - -/* Critical section management. */ - -/* - * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other - * registers. r0 is clobbered. - */ -#define portSET_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, %0 \n" \ - " msr basepri, r0 \n" \ - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ - ) - -/* - * Set basepri back to 0 without effective other registers. - * r0 is clobbered. - */ -#define portCLEAR_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, #0 \n" \ - " msr basepri, r0 \n" \ - :::"r0" \ - ) - -#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() -#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x - - -extern void vPortEnterCritical( void ); -extern void vPortExitCritical( void ); - -#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() -#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() -/*-----------------------------------------------------------*/ - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE unsigned portLONG +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 8 +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); + +#define portYIELD() vPortYieldFromISR() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ + +/* + * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other + * registers. r0 is clobbered. + */ +#define portSET_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, %0 \n" \ + " msr basepri, r0 \n" \ + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ + ) + +/* + * Set basepri back to 0 without effective other registers. + * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see + * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. + */ +#define portCLEAR_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, #0 \n" \ + " msr basepri, r0 \n" \ + :::"r0" \ + ) + +/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a +bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before +disagreeing. */ +#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() + +/* There are an uneven number of items on the initial stack, so +portALIGNMENT_ASSERT_pxCurrentTCB() will trigger false positive asserts. */ +#define portALIGNMENT_ASSERT_pxCurrentTCB ( void ) + +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS/STM32F4xx/library.mk b/flight/PiOS/STM32F4xx/library.mk index c86ea86ce..6a83d367d 100644 --- a/flight/PiOS/STM32F4xx/library.mk +++ b/flight/PiOS/STM32F4xx/library.mk @@ -68,7 +68,7 @@ EXTRAINCDIRS += $(USBDEVLIB)/Core/inc # ifneq ($(FREERTOS_DIR),) FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source -SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4/*.c) -EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4 +SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c) +EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F endif From 17f3c4d4e003032451bf102d500433820dd13441 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 9 Oct 2012 09:57:57 -0500 Subject: [PATCH 504/508] Re-add our code for accessing the run time information in freertos. --- .../Libraries/FreeRTOS/Source/include/task.h | 13 +++++++++++++ .../Common/Libraries/FreeRTOS/Source/tasks.c | 16 ++++++++++++++++ .../Libraries/FreeRTOS/Source/include/task.h | 13 +++++++++++++ .../STM32F10x/Libraries/FreeRTOS/Source/tasks.c | 16 ++++++++++++++++ 4 files changed, 58 insertions(+) diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h index e7a989d40..aa1733b86 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h @@ -1105,6 +1105,19 @@ void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; */ unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
+ * + * Returns the run time of selected task + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The run time of selected task + */ +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); + /* When using trace macros it is sometimes necessary to include tasks.h before FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, so the following two prototypes will cause a compilation error. This can be diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c index 0c43e63d6..8bc546e0d 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c @@ -2282,6 +2282,22 @@ tskTCB *pxNewTCB; #endif /*-----------------------------------------------------------*/ +#if ( INCLUDE_uxTaskGetRunTime == 1 ) + + unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) + { + unsigned long runTime; + + tskTCB *pxTCB; + pxTCB = prvGetTCBFromHandle( xTask ); + runTime = pxTCB->ulRunTimeCounter; + pxTCB->ulRunTimeCounter = 0; + return runTime; + } + +#endif +/*-----------------------------------------------------------*/ + #if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h index e7a989d40..aa1733b86 100755 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h @@ -1105,6 +1105,19 @@ void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; */ unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
+ * + * Returns the run time of selected task + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The run time of selected task + */ +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); + /* When using trace macros it is sometimes necessary to include tasks.h before FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, so the following two prototypes will cause a compilation error. This can be diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c index 0c43e63d6..344208155 100755 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c @@ -2262,6 +2262,22 @@ tskTCB *pxNewTCB; #endif /*-----------------------------------------------------------*/ +#if ( INCLUDE_uxTaskGetRunTime == 1 ) + + unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) + { + unsigned long runTime; + + tskTCB *pxTCB; + pxTCB = prvGetTCBFromHandle( xTask ); + runTime = pxTCB->ulRunTimeCounter; + pxTCB->ulRunTimeCounter = 0; + return runTime; + } + +#endif +/*-----------------------------------------------------------*/ + #if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) From aad1c3bd320df55db6ec3ec467c388f04eab69ef Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 9 Oct 2012 10:08:06 -0500 Subject: [PATCH 505/508] FreeRTOS: Make F1 targets use the FreeRTOS common code from PiOS/Common --- flight/CopterControl/Makefile | 9 +- .../Libraries/FreeRTOS/Source/croutine.c | 380 --- .../FreeRTOS/Source/include/FreeRTOS.h | 522 ---- .../FreeRTOS/Source/include/StackMacros.h | 181 -- .../FreeRTOS/Source/include/croutine.h | 759 ----- .../Libraries/FreeRTOS/Source/include/list.h | 337 --- .../FreeRTOS/Source/include/mpu_wrappers.h | 146 - .../FreeRTOS/Source/include/portable.h | 403 --- .../FreeRTOS/Source/include/projdefs.h | 90 - .../Libraries/FreeRTOS/Source/include/queue.h | 1300 --------- .../FreeRTOS/Source/include/semphr.h | 787 ------ .../Libraries/FreeRTOS/Source/include/task.h | 1315 --------- .../FreeRTOS/Source/include/timers.h | 952 ------- .../Libraries/FreeRTOS/Source/list.c | 204 -- .../Libraries/FreeRTOS/Source/queue.c | 1682 ----------- .../Libraries/FreeRTOS/Source/tasks.c | 2496 ----------------- .../Libraries/FreeRTOS/Source/timers.c | 686 ----- flight/PipXtreme/Makefile | 9 +- 18 files changed, 10 insertions(+), 12248 deletions(-) delete mode 100644 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c delete mode 100755 flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index adb3de6ae..1af7b85f9 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -139,9 +139,10 @@ STMUSBINCDIR = $(STMUSBDIR)/inc CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 DOSFSDIR = $(APPLIBDIR)/dosfs MSDDIR = $(APPLIBDIR)/msd -RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSDIR = $(PIOSCOMMON)/Libraries/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include +RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source DOXYGENDIR = ../Doc/Doxygen AHRSBOOTLOADER = ../Bootloaders/AHRS/ AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc @@ -319,8 +320,8 @@ SRC += $(RTOSSRCDIR)/queue.c SRC += $(RTOSSRCDIR)/tasks.c ## RTOS Portable -SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_1.c +SRC += $(RTOSPORTDIR)/portable/GCC/ARM_CM3/port.c +SRC += $(RTOSPORTDIR)/portable/MemMang/heap_1.c ## Dosfs file system #SRC += $(DOSFSDIR)/dosfs.c @@ -391,7 +392,7 @@ EXTRAINCDIRS += $(DOSFSDIR) EXTRAINCDIRS += $(MSDDIR) EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 +EXTRAINCDIRS += $(RTOSPORTDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c deleted file mode 100644 index 58fb1bf4b..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/croutine.c +++ /dev/null @@ -1,380 +0,0 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - - -/* Lists for ready and blocked co-routines. --------------------*/ -static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ -static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ -static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ -static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ -static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ -static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ - -/* Other file private variables. --------------------------------*/ -corCRCB * pxCurrentCoRoutine = NULL; -static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; -static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; - -/* The initial state of the co-routine when it is created. */ -#define corINITIAL_STATE ( 0 ) - -/* - * Place the co-routine represented by pxCRCB into the appropriate ready queue - * for the priority. It is inserted at the end of the list. - * - * This macro accesses the co-routine ready lists and therefore must not be - * used from within an ISR. - */ -#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ -{ \ - if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ - { \ - uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ -} - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first co-routine. - */ -static void prvInitialiseCoRoutineLists( void ); - -/* - * Co-routines that are readied by an interrupt cannot be placed directly into - * the ready lists (there is no mutual exclusion). Instead they are placed in - * in the pending ready list in order that they can later be moved to the ready - * list by the co-routine scheduler. - */ -static void prvCheckPendingReadyList( void ); - -/* - * Macro that looks at the list of co-routines that are currently delayed to - * see if any require waking. - * - * Co-routines are stored in the queue in the order of their wake time - - * meaning once one co-routine has been found whose timer has not expired - * we need not look any further down the list. - */ -static void prvCheckDelayedList( void ); - -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) -{ -signed portBASE_TYPE xReturn; -corCRCB *pxCoRoutine; - - /* Allocate the memory that will store the co-routine control block. */ - pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); - if( pxCoRoutine ) - { - /* If pxCurrentCoRoutine is NULL then this is the first co-routine to - be created and the co-routine data structures need initialising. */ - if( pxCurrentCoRoutine == NULL ) - { - pxCurrentCoRoutine = pxCoRoutine; - prvInitialiseCoRoutineLists(); - } - - /* Check the priority is within limits. */ - if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) - { - uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; - } - - /* Fill out the co-routine control block from the function parameters. */ - pxCoRoutine->uxState = corINITIAL_STATE; - pxCoRoutine->uxPriority = uxPriority; - pxCoRoutine->uxIndex = uxIndex; - pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; - - /* Initialise all the other co-routine control block parameters. */ - vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); - vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); - - /* Set the co-routine control block as a link back from the xListItem. - This is so we can get back to the containing CRCB from a generic item - in a list. */ - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - - /* Now the co-routine has been initialised it can be added to the ready - list at the correct priority. */ - prvAddCoRoutineToReadyQueue( pxCoRoutine ); - - xReturn = pdPASS; - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) -{ -portTickType xTimeToWake; - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xCoRoutineTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xCoRoutineTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - - if( pxEventList ) - { - /* Also add the co-routine to an event list. If this is done then the - function must be called with interrupts disabled. */ - vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckPendingReadyList( void ) -{ - /* Are there any co-routines waiting to get moved to the ready list? These - are co-routines that have been readied by an ISR. The ISR cannot access - the ready lists itself. */ - while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE ) - { - corCRCB *pxUnblockedCRCB; - - /* The pending ready list can be accessed by an ISR. */ - portDISABLE_INTERRUPTS(); - { - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - } - portENABLE_INTERRUPTS(); - - vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); - prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckDelayedList( void ) -{ -corCRCB *pxCRCB; - - xPassedTicks = xTaskGetTickCount() - xLastTickCount; - while( xPassedTicks ) - { - xCoRoutineTickCount++; - xPassedTicks--; - - /* If the tick count has overflowed we need to swap the ready lists. */ - if( xCoRoutineTickCount == 0 ) - { - xList * pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. If there are - any items in pxDelayedCoRoutineList here then there is an error! */ - pxTemp = pxDelayedCoRoutineList; - pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; - pxOverflowDelayedCoRoutineList = pxTemp; - } - - /* See if this tick has made a timeout expire. */ - while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE ) - { - pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ); - - if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) - { - /* Timeout not yet expired. */ - break; - } - - portDISABLE_INTERRUPTS(); - { - /* The event could have occurred just before this critical - section. If this is the case then the generic list item will - have been moved to the pending ready list and the following - line is still valid. Also the pvContainer parameter will have - been set to NULL so the following lines are also valid. */ - vListRemove( &( pxCRCB->xGenericListItem ) ); - - /* Is the co-routine waiting on an event also? */ - if( pxCRCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxCRCB->xEventListItem ) ); - } - } - portENABLE_INTERRUPTS(); - - prvAddCoRoutineToReadyQueue( pxCRCB ); - } - } - - xLastTickCount = xCoRoutineTickCount; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineSchedule( void ) -{ - /* See if any co-routines readied by events need moving to the ready lists. */ - prvCheckPendingReadyList(); - - /* See if any delayed co-routines have timed out. */ - prvCheckDelayedList(); - - /* Find the highest priority queue that contains ready co-routines. */ - while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) - { - if( uxTopCoRoutineReadyPriority == 0 ) - { - /* No more co-routines to check. */ - return; - } - --uxTopCoRoutineReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines - of the same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); - - /* Call the co-routine. */ - ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); - - return; -} -/*-----------------------------------------------------------*/ - -static void prvInitialiseCoRoutineLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); - vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); - vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); - - /* Start with pxDelayedCoRoutineList using list1 and the - pxOverflowDelayedCoRoutineList using list2. */ - pxDelayedCoRoutineList = &xDelayedCoRoutineList1; - pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) -{ -corCRCB *pxUnblockedCRCB; -signed portBASE_TYPE xReturn; - - /* This function is called from within an interrupt. It can only access - event lists and the pending ready list. This function assumes that a - check has already been made to ensure pxEventList is not empty. */ - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); - - if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) - { - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h deleted file mode 100755 index c12f5d76f..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ /dev/null @@ -1,522 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_xTaskGetIdleTaskHandle - #define INCLUDE_xTaskGetIdleTaskHandle 0 -#endif - -#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle - #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 -#endif - -#ifndef INCLUDE_xQueueGetMutexHolder - #define INCLUDE_xQueueGetMutexHolder 0 -#endif - -#ifndef INCLUDE_pcTaskGetTaskName - #define INCLUDE_pcTaskGetTaskName 0 -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_TIMERS - #define configUSE_TIMERS 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef configASSERT - #define configASSERT( x ) -#endif - -#ifndef portALIGNMENT_ASSERT_pxCurrentTCB - #define portALIGNMENT_ASSERT_pxCurrentTCB configASSERT -#endif - -/* The timers module relies on xTaskGetSchedulerState(). */ -#if configUSE_TIMERS == 1 - - #ifndef configTIMER_TASK_PRIORITY - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. - #endif /* configTIMER_TASK_PRIORITY */ - - #ifndef configTIMER_QUEUE_LENGTH - #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. - #endif /* configTIMER_QUEUE_LENGTH */ - - #ifndef configTIMER_TASK_STACK_DEPTH - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. - #endif /* configTIMER_TASK_STACK_DEPTH */ - -#endif /* configUSE_TIMERS */ - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - -#ifndef portCLEAN_UP_TCB - #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB -#endif - -#ifndef portSETUP_TCB - #define portSETUP_TCB( pxTCB ) ( void ) pxTCB -#endif - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0U -#endif - -#if ( configQUEUE_REGISTRY_SIZE < 1 ) - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - -#ifndef portPOINTER_SIZE_TYPE - #define portPOINTER_SIZE_TYPE unsigned long -#endif - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceTASK_PRIORITY_INHERIT - /* Called when a task attempts to take a mutex that is already held by a - lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task - that holds the mutex. uxInheritedPriority is the priority the mutex holder - will inherit (the priority of the task that is attempting to obtain the - muted. */ - #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) -#endif - -#ifndef traceTASK_PRIORITY_DISINHERIT - /* Called when a task releases a mutex, the holding of which had resulted in - the task inheriting the priority of a higher priority task. - pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the - mutex. uxOriginalPriority is the task's configured (base) priority. */ - #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceMOVED_TASK_TO_READY_STATE - #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) -#endif - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED( ucQueueType ) -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED - #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED() -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef traceTIMER_CREATE - #define traceTIMER_CREATE( pxNewTimer ) -#endif - -#ifndef traceTIMER_CREATE_FAILED - #define traceTIMER_CREATE_FAILED() -#endif - -#ifndef traceTIMER_COMMAND_SEND - #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) -#endif - -#ifndef traceTIMER_EXPIRED - #define traceTIMER_EXPIRED( pxTimer ) -#endif - -#ifndef traceTIMER_COMMAND_RECEIVED - #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. - #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h deleted file mode 100755 index daf3ce408..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/StackMacros.h +++ /dev/null @@ -1,181 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h deleted file mode 100755 index f2843cde2..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/croutine.h +++ /dev/null @@ -1,759 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include croutine.h" -#endif - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( ( xTicksToDelay ) > 0 ) \ - { \ - vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ - } \ - crSET_STATE0( ( xHandle ) ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ - } \ - if( *( pxResult ) == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *( pxResult ) = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h deleted file mode 100755 index 28d4f248e..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/list.h +++ /dev/null @@ -1,337 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) - -/* - * Access macro to get the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_OWNER( pxListItem ) ( pxListItem )->pvOwner - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) - -/* - * Access macro to retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro the retrieve the value of the list item at the head of a given - * list. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = ( pxList ); \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) - -/* - * This provides a crude means of knowing if a list has been initialised, as - * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() - * function. - */ -#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h deleted file mode 100755 index be49c3d88..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ /dev/null @@ -1,146 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueGenericCreate MPU_xQueueGenericCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h deleted file mode 100755 index 88cfbb2b7..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/portable.h +++ /dev/null @@ -1,403 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h deleted file mode 100755 index c69db9237..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/projdefs.h +++ /dev/null @@ -1,90 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -#endif /* PROJDEFS_H */ - - - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h deleted file mode 100755 index e48cf07a6..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/queue.h +++ /dev/null @@ -1,1300 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h" must appear in source files before "include queue.h" -#endif - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - -/** - * Type by which queues are referenced. For example, a call to xQueueCreate - * returns (via a pointer parameter) an xQueueHandle variable that can then - * be used as a parameter to xQueueSend(), xQueueReceive(), etc. - */ -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* For internal use only. These definitions *must* match those in queue.c. */ -#define queueQUEUE_TYPE_BASE ( 0U ) -#define queueQUEUE_TYPE_MUTEX ( 1U ) -#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) -#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) -#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle pxQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ); - -/* - * Utilities to query queues that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex(), - * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling - * these functions directly. - */ -xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); -void* xQueueGetMutexHolder( xQueueHandle xSemaphore ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); - -/* - * Reset a queue back to its original empty state. pdPASS is returned if the - * queue is successfully reset. pdFAIL is returned if the queue could not be - * reset because there are tasks blocked on the queue waiting to either - * receive from the queue or send to the queue. - */ -#define xQueueReset( pxQueue ) xQueueGenericReset( pxQueue, pdFALSE ) - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0U - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - -/* - * Generic version of the queue creation function, which is in turn called by - * any queue, semaphore or mutex creation function or macro. - */ -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ); - -/* Not public API functions. */ -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ); - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h deleted file mode 100755 index 65c77c7c9..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/semphr.h +++ /dev/null @@ -1,787 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h" must appear in source files before "include semphr.h" -#endif - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) \ - { \ - ( xSemaphore ) = xQueueGenericCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ - if( ( xSemaphore ) != NULL ) \ - { \ - xSemaphoreGive( ( xSemaphore ) ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreTakeFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to take a semaphore from an ISR. The semaphore must have - * previously been created with a call to vSemaphoreCreateBinary() or - * xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR, however taking a semaphore from an ISR - * is not a common operation. It is likely to only be useful when taking a - * counting semaphore when an interrupt is obtaining an object from a resource - * pool (when the semaphore count indicates the number of resources available). - * - * @param xSemaphore A handle to the semaphore being taken. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully taken, otherwise - * pdFALSE - */ -#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) - -/** - * semphr. h - *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
- * - * Delete a semaphore. This function must be used with care. For example, - * do not delete a mutex type semaphore if the mutex is held by a task. - * - * @param xSemaphore A handle to the semaphore to be deleted. - * - * \page vSemaphoreDelete vSemaphoreDelete - * \ingroup Semaphores - */ -#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) ( xSemaphore ) ) - -/** - * semphr.h - *
xTaskHandle xSemaphoreGetMutexHolder( xSemaphoreHandle xMutex );
- * - * If xMutex is indeed a mutex type semaphore, return the current mutex holder. - * If xMutex is not a mutex type semaphore, or the mutex is available (not held - * by a task), return NULL. - * - * Note: This Is is a good way of determining if the calling task is the mutex - * holder, but not a good way of determining the identity of the mutex holder as - * the holder may change between the function exiting and the returned value - * being tested. - */ -#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) - -#endif /* SEMAPHORE_H */ - - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h deleted file mode 100755 index aa1733b86..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/task.h +++ /dev/null @@ -1,1315 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - Selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef TASK_H -#define TASK_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include task.h" -#endif - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V7.2.0" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
portTickType xTaskGetTickCountFromISR( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * This is a version of xTaskGetTickCount() that is safe to be called from an - * ISR - provided that portTickType is the natural word size of the - * microcontroller being used or interrupt nesting is either not supported or - * not being used. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
- * - * @return The text (human readable) name of the task referenced by the handle - * xTaskToQueury. A task can query its own name by either passing in its own - * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be - * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. - * - * \page pcTaskGetTaskName pcTaskGetTaskName - * \ingroup TaskUtils - */ -signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in words, so on a 32 bit machine - * a value of 1 means 4 bytes) since the task started. The smaller the returned - * number the closer the task has come to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
- * - * Returns the run time of selected task - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The run time of selected task - */ -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); - -/* When using trace macros it is sometimes necessary to include tasks.h before -FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, -so the following two prototypes will cause a compilation error. This can be -fixed by simply guarding against the inclusion of these two prototypes unless -they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration -constant. */ -#ifdef configUSE_APPLICATION_TASK_TAG - #if configUSE_APPLICATION_TASK_TAG == 1 - /** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - - /** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ -#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - -/** - * xTaskGetIdleTaskHandle() is only available if - * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the idle task. It is not valid to call - * xTaskGetIdleTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTaskGetIdleTaskHandle( void ); - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * This function performs nearly the same function as vTaskPlaceOnEventList(). - * The difference being that this function does not permit tasks to block - * indefinitely, whereas vTaskPlaceOnEventList() does. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -/* - * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. - */ -unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ); - -/* - * Set the uxTCBNumber of the task referenced by the xTask parameter to - * ucHandle. - */ -void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ); - - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h deleted file mode 100755 index 5f62368f5..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/include/timers.h +++ /dev/null @@ -1,952 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef TIMERS_H -#define TIMERS_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include timers.h" -#endif - -#include "portable.h" -#include "list.h" -#include "task.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* IDs for commands that can be sent/received on the timer queue. These are to -be used solely through the macros that make up the public software timer API, -as defined below. */ -#define tmrCOMMAND_START 0 -#define tmrCOMMAND_STOP 1 -#define tmrCOMMAND_CHANGE_PERIOD 2 -#define tmrCOMMAND_DELETE 3 - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - - /** - * Type by which software timers are referenced. For example, a call to - * xTimerCreate() returns an xTimerHandle variable that can then be used to - * reference the subject timer in calls to other software timer API functions - * (for example, xTimerStart(), xTimerReset(), etc.). - */ -typedef void * xTimerHandle; - -/* Define the prototype to which timer callback functions must conform. */ -typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); - -/** - * xTimerHandle xTimerCreate( const signed char *pcTimerName, - * portTickType xTimerPeriodInTicks, - * unsigned portBASE_TYPE uxAutoReload, - * void * pvTimerID, - * tmrTIMER_CALLBACK pxCallbackFunction ); - * - * Creates a new software timer instance. This allocates the storage required - * by the new timer, initialises the new timers internal state, and returns a - * handle by which the new timer can be referenced. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param pcTimerName A text name that is assigned to the timer. This is done - * purely to assist debugging. The kernel itself only ever references a timer by - * its handle, and never by its name. - * - * @param xTimerPeriodInTicks The timer period. The time is defined in tick periods so - * the constant portTICK_RATE_MS can be used to convert a time that has been - * specified in milliseconds. For example, if the timer must expire after 100 - * ticks, then xTimerPeriodInTicks should be set to 100. Alternatively, if the timer - * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) - * provided configTICK_RATE_HZ is less than or equal to 1000. - * - * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will - * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. If - * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and - * enter the dormant state after it expires. - * - * @param pvTimerID An identifier that is assigned to the timer being created. - * Typically this would be used in the timer callback function to identify which - * timer expired when the same callback function is assigned to more than one - * timer. - * - * @param pxCallbackFunction The function to call when the timer expires. - * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, - * which is "void vCallbackFunction( xTimerHandle xTimer );". - * - * @return If the timer is successfully create then a handle to the newly - * created timer is returned. If the timer cannot be created (because either - * there is insufficient FreeRTOS heap remaining to allocate the timer - * structures, or the timer period was set to 0) then 0 is returned. - * - * Example usage: - * - * #define NUM_TIMERS 5 - * - * // An array to hold handles to the created timers. - * xTimerHandle xTimers[ NUM_TIMERS ]; - * - * // An array to hold a count of the number of times each timer expires. - * long lExpireCounters[ NUM_TIMERS ] = { 0 }; - * - * // Define a callback function that will be used by multiple timer instances. - * // The callback function does nothing but count the number of times the - * // associated timer expires, and stop the timer once the timer has expired - * // 10 times. - * void vTimerCallback( xTimerHandle pxTimer ) - * { - * long lArrayIndex; - * const long xMaxExpiryCountBeforeStopping = 10; - * - * // Optionally do something if the pxTimer parameter is NULL. - * configASSERT( pxTimer ); - * - * // Which timer expired? - * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); - * - * // Increment the number of times that pxTimer has expired. - * lExpireCounters[ lArrayIndex ] += 1; - * - * // If the timer has expired 10 times then stop it from running. - * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) - * { - * // Do not use a block time if calling a timer API function from a - * // timer callback function, as doing so could cause a deadlock! - * xTimerStop( pxTimer, 0 ); - * } - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start some timers. Starting the timers before the scheduler - * // has been started means the timers will start running immediately that - * // the scheduler starts. - * for( x = 0; x < NUM_TIMERS; x++ ) - * { - * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. - * ( 100 * x ), // The timer period in ticks. - * pdTRUE, // The timers will auto-reload themselves when they expire. - * ( void * ) x, // Assign each timer a unique id equal to its array index. - * vTimerCallback // Each timer calls the same callback when it expires. - * ); - * - * if( xTimers[ x ] == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timers running as they have already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; - -/** - * void *pvTimerGetTimerID( xTimerHandle xTimer ); - * - * Returns the ID assigned to the timer. - * - * IDs are assigned to timers using the pvTimerID parameter of the call to - * xTimerCreated() that was used to create the timer. - * - * If the same callback function is assigned to multiple timers then the timer - * ID can be used within the callback function to identify which timer actually - * expired. - * - * @param xTimer The timer being queried. - * - * @return The ID assigned to the timer being queried. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - */ -void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); - * - * Queries a timer to see if it is active or dormant. - * - * A timer will be dormant if: - * 1) It has been created but not started, or - * 2) It is an expired on-shot timer that has not been restarted. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param xTimer The timer being queried. - * - * @return pdFALSE will be returned if the timer is dormant. A value other than - * pdFALSE will be returned if the timer is active. - * - * Example usage: - * - * // This function assumes xTimer has already been created. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is active, do something. - * } - * else - * { - * // xTimer is not active, do something else. - * } - * } - */ -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * xTimerGetTimerDaemonTaskHandle() is only available if - * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the timer service/daemon task. It it not valid - * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); - -/** - * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStart() starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerStart() has equivalent functionality - * to the xTimerReset() API function. - * - * Starting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerStart() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerStart() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerStart() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() - * to be available. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the start command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStop() stops a timer that was previously started using either of the - * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), - * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. - * - * Stopping a timer ensures the timer is not in the active state. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() - * to be available. - * - * @param xTimer The handle of the timer being stopped. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the stop command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerChangePeriod() changes the period of a timer that was previously - * created using the xTimerCreate() API function. - * - * xTimerChangePeriod() can be called to change the period of an active or - * dormant state timer. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerChangePeriod() to be available. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the change period command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerChangePeriod() was called. xBlockTime is ignored if - * xTimerChangePeriod() is called before the scheduler is started. - * - * @return pdFAIL will be returned if the change period command could not be - * sent to the timer command queue even after xBlockTime ticks had passed. - * pdPASS will be returned if the command was successfully sent to the timer - * command queue. When the command is actually processed will depend on the - * priority of the timer service/daemon task relative to other tasks in the - * system. The timer service/daemon task priority is set by the - * configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This function assumes xTimer has already been created. If the timer - * // referenced by xTimer is already active when it is called, then the timer - * // is deleted. If the timer referenced by xTimer is not active when it is - * // called, then the period of the timer is set to 500ms and the timer is - * // started. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is already active - delete it. - * xTimerDelete( xTimer ); - * } - * else - * { - * // xTimer is not active, change its period to 500ms. This will also - * // cause the timer to start. Block for a maximum of 100 ticks if the - * // change period command cannot immediately be sent to the timer - * // command queue. - * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) - * { - * // The command was successfully sent. - * } - * else - * { - * // The command could not be sent, even after waiting for 100 ticks - * // to pass. Take appropriate action here. - * } - * } - * } - */ - #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerDelete() deletes a timer that was previously created using the - * xTimerCreate() API function. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerDelete() to be available. - * - * @param xTimer The handle of the timer being deleted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the delete command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() - * is called before the scheduler is started. - * - * @return pdFAIL will be returned if the delete command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerChangePeriod() API function example usage scenario. - */ -#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerReset() re-starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerReset() will cause the timer to - * re-evaluate its expiry time so that it is relative to when xTimerReset() was - * called. If the timer was in the dormant state then xTimerReset() has - * equivalent functionality to the xTimerStart() API function. - * - * Resetting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerReset() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerReset() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerReset() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() - * to be available. - * - * @param xTimer The handle of the timer being reset/started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the reset command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer. - * - * xTimerHandle xBacklightTimer = NULL; - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press event handler. - * void vKeyPressEventHandler( char cKey ) - * { - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. Wait 10 ticks for the command to be successfully sent - * // if it cannot be sent immediately. - * vSetBacklightState( BACKLIGHT_ON ); - * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start the one-shot timer that is responsible for turning - * // the back-light off if no keys are pressed within a 5 second period. - * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. - * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. - * pdFALSE, // The timer is a one-shot timer. - * 0, // The id is not used by the callback so can take any value. - * vBacklightTimerCallback // The callback function that switches the LCD back-light off. - * ); - * - * if( xBacklightTimer == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timer running as it has already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStart() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStartFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStartFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStartFromISR() function. If - * xTimerStartFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerStartFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then restart the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The start command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStop() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being stopped. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStopFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStopFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStopFromISR() function. If - * xTimerStopFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the timer should be simply stopped. - * - * // The interrupt service routine that stops the timer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - simply stop the timer. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The stop command was not executed successfully. Take appropriate - * // action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerChangePeriod() that can be called from an interrupt - * service routine. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerChangePeriodFromISR() writes a message to the - * timer command queue, so has the potential to transition the timer service/ - * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() - * causes the timer service/daemon task to leave the Blocked state, and the - * timer service/daemon task has a priority equal to or greater than the - * currently executing task (the task that was interrupted), then - * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the - * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets - * this value to pdTRUE then a context switch should be performed before the - * interrupt exits. - * - * @return pdFAIL will be returned if the command to change the timers period - * could not be sent to the timer command queue. pdPASS will be returned if the - * command was successfully sent to the timer command queue. When the command - * is actually processed will depend on the priority of the timer service/daemon - * task relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the period of xTimer should be changed to 500ms. - * - * // The interrupt service routine that changes the period of xTimer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - change the period of xTimer to 500ms. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The command to change the timers period was not executed - * // successfully. Take appropriate action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerReset() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer that is to be started, reset, or - * restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerResetFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerResetFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerResetFromISR() function. If - * xTimerResetFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerResetFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/* - * Functions beyond this part are not part of the public API and are intended - * for use by the kernel only. - */ -portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TIMERS_H */ - - - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c deleted file mode 100755 index 9ae5d86e4..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/list.c +++ /dev/null @@ -1,204 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem *pxIterator; -portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex-M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ -xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c deleted file mode 100755 index 4748860db..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/queue.c +++ /dev/null @@ -1,1682 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#if ( configUSE_CO_ROUTINES == 1 ) - #include "croutine.h" -#endif - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and xTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0U ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) - -/* These definitions *must* match those in queue.h. */ -#define queueQUEUE_TYPE_BASE ( 0U ) -#define queueQUEUE_TYPE_MUTEX ( 1U ) -#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) -#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) -#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - volatile signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - volatile signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned char ucQueueNumber; - unsigned char ucQueueType; - #endif - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) PRIVILEGED_FUNCTION; -unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) PRIVILEGED_FUNCTION; -xTaskHandle xQueueGetMutexHolder( xQueueHandle xSemaphore ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ - taskENTER_CRITICAL(); \ - { \ - if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL() -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) -{ - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - { - pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); - pxQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxQueue->pcWriteTo = pxQueue->pcHead; - pxQueue->pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( unsigned portBASE_TYPE ) 1U ) * pxQueue->uxItemSize ); - pxQueue->xRxLock = queueUNLOCKED; - pxQueue->xTxLock = queueUNLOCKED; - - if( xNewQueue == pdFALSE ) - { - /* If there are tasks blocked waiting to read from the queue, then - the tasks will remain blocked as after this function exits the queue - will still be empty. If there are tasks blocked waiting to write to - the queue, then one should be unblocked as after this function exits - it will be possible to write to it. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - /* Ensure the event queues start in the correct state. */ - vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); - } - } - taskEXIT_CRITICAL(); - - /* A value is returned for calling semantic consistency with previous - versions. */ - return pdPASS; -} -/*-----------------------------------------------------------*/ - -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; -xQueueHandle xReturn = NULL; - - /* Remove compiler warnings about unused parameters should - configUSE_TRACE_FACILITY not be set to 1. */ - ( void ) ucQueueType; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - xQueueGenericReset( pxNewQueue, pdTRUE ); - #if ( configUSE_TRACE_FACILITY == 1 ) - { - pxNewQueue->ucQueueType = ucQueueType; - } - #endif /* configUSE_TRACE_FACILITY */ - - traceQUEUE_CREATE( pxNewQueue ); - xReturn = pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED( ucQueueType ); - vPortFree( pxNewQueue ); - } - } - } - - configASSERT( xReturn ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) - { - xQUEUE *pxNewQueue; - - /* Prevent compiler warnings about unused parameters if - configUSE_TRACE_FACILITY does not equal 1. */ - ( void ) ucQueueType; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; - pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - pxNewQueue->ucQueueType = ucQueueType; - } - #endif - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceCREATE_MUTEX( pxNewQueue ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - configASSERT( pxNewQueue ); - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xQueueGetMutexHolder == 1 ) ) - - void* xQueueGetMutexHolder( xQueueHandle xSemaphore ) - { - void *pxReturn; - - /* This function is called by xSemaphoreGetMutexHolder(), and should not - be called directly. Note: This is is a good way of determining if the - calling task is the mutex holder, but not a good way of determining the - identity of the mutex holder, as the holder may change between the - following critical section exiting and the function returning. */ - taskENTER_CRITICAL(); - { - if( xSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) - { - pxReturn = ( void * ) xSemaphore->pxMutexHolder; - } - else - { - pxReturn = NULL; - } - } - taskEXIT_CRITICAL(); - - return pxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_RECURSIVE_MUTEXES == 1 ) - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - else - { - traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueGenericCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - configASSERT( pxHandle ); - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - if( pxHigherPriorityTaskWoken != NULL ) - { - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - if( pxHigherPriorityTaskWoken != NULL ) - { - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - configASSERT( pxQueue ); - - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) - { - return pxQueue->ucQueueNumber; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) - { - pxQueue->ucQueueNumber = ucQueueNumber; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) - { - return pxQueue->ucQueueType; - } - -#endif -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( xCoRoutinePreviouslyWoken == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( ( *pxCoRoutineWoken ) == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) - { - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements. - It can result in vListInsert() being called on a list that can only - possibly ever have one item in it, so the list will be fast, but even - so it should be called with the scheduler locked and not from a critical - section. */ - - /* Only do anything if there are no messages in the queue. This function - will not actually cause the task to block, just place it on a blocked - list. It will not block until the scheduler is unlocked - at which - time a yield will be performed. If an item is added to the queue while - the queue is locked, and the calling task blocks on the queue, then the - calling task will be immediately unblocked when the queue is unlocked. */ - prvLockQueue( pxQueue ); - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) - { - /* There is nothing in the queue, block for the specified period. */ - vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - } - prvUnlockQueue( pxQueue ); - } - -#endif - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c deleted file mode 100755 index 344208155..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/tasks.c +++ /dev/null @@ -1,2496 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "timers.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ - unsigned portBASE_TYPE uxTaskNumber; /*< This stores a number specifically for use by third party trace code. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5U ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ - traceMOVED_TASK_TO_READY_STATE( pxTCB ) \ - if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = ( pxTCB )->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -portTickType xItemValue; \ - \ - /* Is the tick count greater than or equal to the wake time of the first \ - task referenced from the delayed tasks list? */ \ - if( xTickCount >= xNextTaskUnblockTime ) \ - { \ - for( ;; ) \ - { \ - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ - { \ - /* The delayed list is empty. Set xNextTaskUnblockTime to the \ - maximum possible value so it is extremely unlikely that the \ - if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ - time through. */ \ - xNextTaskUnblockTime = portMAX_DELAY; \ - break; \ - } \ - else \ - { \ - /* The delayed list is not empty, get the value of the item at \ - the head of the delayed list. This is the time at which the \ - task at the head of the delayed list should be removed from \ - the Blocked state. */ \ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ - xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ - \ - if( xTickCount < xItemValue ) \ - { \ - /* It is not time to unblock this item yet, but the item \ - value is the time at which the task at the head of the \ - blocked list should be removed from the Blocked state - \ - so record the item value in xNextTaskUnblockTime. */ \ - xNextTaskUnblockTime = xItemValue; \ - break; \ - } \ - \ - /* It is time to remove the item from the Blocked state. */ \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer != NULL ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ - } \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) - -/* Callback function prototypes. --------------------------*/ -extern void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName ); -extern void vApplicationTickHook( void ); - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * The currently executing task is entering the Blocked state. Add the task to - * either the current or the overflow delayed task list. - */ -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - configASSERT( pxTaskCode ); - configASSERT( ( ( uxPriority & ( ~portPRIVILEGE_BIT ) ) < configMAX_PRIORITIES ) ); - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); - - /* Check the alignment of the calculated top of stack is correct. */ - configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* Check the alignment of the stack buffer is correct. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* Check the alignment of the initialised stack. */ - portALIGNMENT_ASSERT_pxCurrentTCB( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - taskENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( pxCurrentTCB == NULL ) - { - /* There are no other tasks, or all the other tasks are in - the suspended state - make this the current task. */ - pxCurrentTCB = pxNewTCB; - - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - portSETUP_TCB( pxNewTCB ); - traceTASK_CREATE( pxNewTCB ); - } - taskEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED(); - } - - if( xReturn == pdPASS ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - taskEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - configASSERT( pxPreviousWakeTime ); - configASSERT( ( xTimeIncrement > 0U ) ); - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay != pdFALSE ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0U ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - taskEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority; - portBASE_TYPE xYieldRequired = pdFALSE; - - configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - taskENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - taskEXIT_CRITICAL(); - - if( ( void * ) pxTaskToSuspend == NULL ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* We have just suspended the current task. */ - portYIELD_WITHIN_API(); - } - else - { - /* The scheduler is not running, but the task that was pointed - to by pxCurrentTCB has just been suspended and pxCurrentTCB - must be adjusted to point to a different task. */ - if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) - { - /* No other tasks are ready, so set pxCurrentTCB back to - NULL so when the next task is created pxCurrentTCB will - be set to point to it no matter what its relative priority - is. */ - pxCurrentTCB = NULL; - } - else - { - vTaskSwitchContext(); - } - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* It does not make sense to check if the calling task is suspended. */ - configASSERT( xTask ); - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* It does not make sense to resume the calling task. */ - configASSERT( pxTaskToResume ); - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - taskENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxTaskToResume ); - - pxTCB = ( tskTCB * ) pxTaskToResume; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - { - /* Create the idle task, storing its handle in xIdleTaskHandle so it can - be returned by the xTaskGetIdleTaskHandle() function. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); - } - #else - { - /* Create the idle task without storing its handle. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); - } - #endif - - #if ( configUSE_TIMERS == 1 ) - { - if( xReturn == pdPASS ) - { - xReturn = xTimerCreateTimerTask(); - } - } - #endif - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0U; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() != pdFALSE ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } - - /* This line will only be reached if the kernel could not be started. */ - configASSERT( xReturn ); -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* If uxSchedulerSuspended is zero then this function does not match a - previous call to vTaskSuspendAll(). */ - configASSERT( uxSchedulerSuspended ); - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - taskENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - taskEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - taskENTER_CRITICAL(); - { - xTicks = xTickCount; - } - taskEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -portTickType xTaskGetTickCountFromISR( void ) -{ -portTickType xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - xReturn = xTickCount; - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_pcTaskGetTaskName == 1 ) - - signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) - { - tskTCB *pxTCB; - - /* If null is passed in here then the name of the calling task is being queried. */ - pxTCB = prvGetTCBFromHandle( xTaskToQuery ); - configASSERT( pxTCB ); - return &( pxTCB->pcTaskName[ 0 ] ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); - #else - ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Divide ulTotalRunTime by 100 to make the percentage caluclations - simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ - ulTotalRunTime /= 100UL; - - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - xTaskHandle xTaskGetIdleTaskHandle( void ) - { - /* If xTaskGetIdleTaskHandle() is called before the scheduler has been - started, then xIdleTaskHandle will be NULL. */ - configASSERT( ( xIdleTaskHandle != NULL ) ); - return xIdleTaskHandle; - } - -#endif - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - -void vTaskIncrementTick( void ) -{ -tskTCB * pxTCB; - - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0U ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); - - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) - { - /* The new current delayed list is empty. Set - xNextTaskUnblockTime to the maximum possible value so it is - extremely unlikely that the - if( xTickCount >= xNextTaskUnblockTime ) test will pass until - there is an item in the delayed list. */ - xNextTaskUnblockTime = portMAX_DELAY; - } - else - { - /* The new current delayed list is not empty, get the value of - the item at the head of the delayed list. This is the time at - which the task at the head of the delayed list should be removed - from the Blocked state. */ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); - xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); - } - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xTCB->pxTaskTag = pxHookFunction; - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - taskEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - } - else - { - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter; - - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); - #else - ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - configASSERT( uxTopReadyPriority ); - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - } -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - #endif -} -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) - { - portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements - - it should be called from a critical section. */ - - - /* Place the event list item of the TCB in the appropriate event list. - In this case it is assume that this is the only task that is going to - be waiting on this event list, so the faster vListInsertEnd() function - can be used in place of vListInsert. */ - vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove this task from the ready list before adding it to the - blocked list as the same list item is used for both lists. This - function is called form a critical section. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - -#endif /* configUSE_TIMERS */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. - - This function assumes that a check has already been made to ensure that - pxEventList is not empty. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - configASSERT( pxUnblockedTCB ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - configASSERT( pxTimeOut ); - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - configASSERT( pxTimeOut ); - configASSERT( pxTicksToWait ); - - taskENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ) - { - unsigned portBASE_TYPE uxReturn; - tskTCB *pxTCB; - - if( xTask != NULL ) - { - pxTCB = ( tskTCB * ) xTask; - uxReturn = pxTCB->uxTaskNumber; - } - else - { - uxReturn = 0U; - } - - return uxReturn; - } -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ) - { - tskTCB *pxTCB; - - if( xTask != NULL ) - { - pxTCB = ( tskTCB * ) xTask; - pxTCB->uxTaskNumber = uxHandle; - } - } -#endif - - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( xListIsEmpty == pdFALSE ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - taskEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) -{ - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* If the task entering the blocked state was placed at the head of the - list of blocked tasks then xNextTaskUnblockTime needs to be updated - too. */ - if( xTimeToWake < xNextTaskUnblockTime ) - { - xNextTaskUnblockTime = xTimeToWake; - } - } -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - PRIVILEGED_DATA static char pcStatusString[ configMAX_TASK_NAME_LEN + 30 ]; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0UL ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time has the task used? - This will always be rounded down to the nearest integer. - ulTotalRunTime has already been divided by 100. */ - ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - #endif - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - #endif - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetRunTime == 1 ) - - unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) - { - unsigned long runTime; - - tskTCB *pxTCB; - pxTCB = prvGetTCBFromHandle( xTask ); - runTime = pxTCB->ulRunTimeCounter; - pxTCB->ulRunTimeCounter = 0; - return runTime; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0U; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* This call is required specifically for the TriCore port. It must be - above the vPortFree() calls. The call is also used by ports/demos that - want to allocate and clean RAM statically. */ - portCLEAN_UP_TCB( pxTCB ); - - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - configASSERT( pxMutexHolder ); - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - - traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding the task into the new - ready list. */ - traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - ( pxCurrentTCB->uxCriticalNesting )++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0U ) - { - ( pxCurrentTCB->uxCriticalNesting )--; - - if( pxCurrentTCB->uxCriticalNesting == 0U ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c deleted file mode 100755 index 0be294277..000000000 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/timers.c +++ /dev/null @@ -1,686 +0,0 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "timers.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. This #if is closed at the very bottom -of this file. If you want to include software timer functionality then ensure -configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#if ( configUSE_TIMERS == 1 ) - -/* Misc definitions. */ -#define tmrNO_DELAY ( portTickType ) 0U - -/* The definition of the timers themselves. */ -typedef struct tmrTimerControl -{ - const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ - xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ - portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ - unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ - void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ - tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ -} xTIMER; - -/* The definition of messages that can be sent and received on the timer -queue. */ -typedef struct tmrTimerQueueMessage -{ - portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ - portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ - xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ -} xTIMER_MESSAGE; - - -/* The list in which active timers are stored. Timers are referenced in expire -time order, with the nearest expiry time at the front of the list. Only the -timer service task is allowed to access xActiveTimerList. */ -PRIVILEGED_DATA static xList xActiveTimerList1; -PRIVILEGED_DATA static xList xActiveTimerList2; -PRIVILEGED_DATA static xList *pxCurrentTimerList; -PRIVILEGED_DATA static xList *pxOverflowTimerList; - -/* A queue that is used to send commands to the timer service task. */ -PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Initialise the infrastructure used by the timer service task if it has not - * been initialised already. - */ -static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; - -/* - * The timer service task (daemon). Timer functionality is controlled by this - * task. Other tasks communicate with the timer service task using the - * xTimerQueue queue. - */ -static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; - -/* - * Called by the timer service task to interpret and process a command it - * received on the timer queue. - */ -static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; - -/* - * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, - * depending on if the expire time causes a timer counter overflow. - */ -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; - -/* - * An active timer has reached its expire time. Reload the timer if it is an - * auto reload timer, then call its callback. - */ -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; - -/* - * The tick count has overflowed. Switch the timer lists after ensuring the - * current timer list does not still reference some timers. - */ -static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; - -/* - * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE - * if a tick count overflow occurred since prvSampleTimeNow() was last called. - */ -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; - -/* - * If the timer list contains any active timers then return the expire time of - * the timer that will expire first and set *pxListWasEmpty to false. If the - * timer list does not contain any timers then return 0 and set *pxListWasEmpty - * to pdTRUE. - */ -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; - -/* - * If a timer has expired, process it. Otherwise, block the timer service task - * until either a timer does expire or a command is received. - */ -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; - -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerCreateTimerTask( void ) -{ -portBASE_TYPE xReturn = pdFAIL; - - /* This function is called when the scheduler is started if - configUSE_TIMERS is set to 1. Check that the infrastructure used by the - timer service task has been created/initialised. If timers have already - been created then the initialisation will already have been performed. */ - prvCheckForValidListAndQueue(); - - if( xTimerQueue != NULL ) - { - #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - { - /* Create the timer task, storing its handle in xTimerTaskHandle so - it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle ); - } - #else - { - /* Create the timer task without storing its handle. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL); - } - #endif - } - - configASSERT( xReturn ); - return xReturn; -} -/*-----------------------------------------------------------*/ - -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) -{ -xTIMER *pxNewTimer; - - /* Allocate the timer structure. */ - if( xTimerPeriodInTicks == ( portTickType ) 0U ) - { - pxNewTimer = NULL; - configASSERT( ( xTimerPeriodInTicks > 0 ) ); - } - else - { - pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); - if( pxNewTimer != NULL ) - { - /* Ensure the infrastructure used by the timer service task has been - created/initialised. */ - prvCheckForValidListAndQueue(); - - /* Initialise the timer structure members using the function parameters. */ - pxNewTimer->pcTimerName = pcTimerName; - pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; - pxNewTimer->uxAutoReload = uxAutoReload; - pxNewTimer->pvTimerID = pvTimerID; - pxNewTimer->pxCallbackFunction = pxCallbackFunction; - vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); - - traceTIMER_CREATE( pxNewTimer ); - } - else - { - traceTIMER_CREATE_FAILED(); - } - } - - return ( xTimerHandle ) pxNewTimer; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) -{ -portBASE_TYPE xReturn = pdFAIL; -xTIMER_MESSAGE xMessage; - - /* Send a message to the timer service task to perform a particular action - on a particular timer definition. */ - if( xTimerQueue != NULL ) - { - /* Send a command to the timer service task to start the xTimer timer. */ - xMessage.xMessageID = xCommandID; - xMessage.xMessageValue = xOptionalValue; - xMessage.pxTimer = ( xTIMER * ) xTimer; - - if( pxHigherPriorityTaskWoken == NULL ) - { - if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); - } - else - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); - } - } - else - { - xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); - } - - traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) - { - /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been - started, then xTimerTaskHandle will be NULL. */ - configASSERT( ( xTimerTaskHandle != NULL ) ); - return xTimerTaskHandle; - } - -#endif -/*-----------------------------------------------------------*/ - -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) -{ -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove the timer from the list of active timers. A check has already - been performed to ensure the list is not empty. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - traceTIMER_EXPIRED( pxTimer ); - - /* If the timer is an auto reload timer then calculate the next - expiry time and re-insert the timer in the list of active timers. */ - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* This is the only time a timer is inserted into a list using - a time relative to anything other than the current time. It - will therefore be inserted into the correct list relative to - the time this task thinks it is now, even if a command to - switch lists due to a tick count overflow is already waiting in - the timer queue. */ - if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Reload it now. */ - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - - /* Call the timer callback. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); -} -/*-----------------------------------------------------------*/ - -static void prvTimerTask( void *pvParameters ) -{ -portTickType xNextExpireTime; -portBASE_TYPE xListWasEmpty; - - /* Just to avoid compiler warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* Query the timers list to see if it contains any timers, and if so, - obtain the time at which the next timer will expire. */ - xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); - - /* If a timer has expired, process it. Otherwise, block this task - until either a timer does expire, or a command is received. */ - prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); - - /* Empty the command queue. */ - prvProcessReceivedCommands(); - } -} -/*-----------------------------------------------------------*/ - -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) -{ -portTickType xTimeNow; -portBASE_TYPE xTimerListsWereSwitched; - - vTaskSuspendAll(); - { - /* Obtain the time now to make an assessment as to whether the timer - has expired or not. If obtaining the time causes the lists to switch - then don't process this timer as any timers that remained in the list - when the lists were switched will have been processed within the - prvSampelTimeNow() function. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - if( xTimerListsWereSwitched == pdFALSE ) - { - /* The tick count has not overflowed, has the timer expired? */ - if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) - { - xTaskResumeAll(); - prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); - } - else - { - /* The tick count has not overflowed, and the next expire - time has not been reached yet. This task should therefore - block to wait for the next expire time or a command to be - received - whichever comes first. The following line cannot - be reached unless xNextExpireTime > xTimeNow, except in the - case when the current timer list is empty. */ - vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); - - if( xTaskResumeAll() == pdFALSE ) - { - /* Yield to wait for either a command to arrive, or the block time - to expire. If a command arrived between the critical section being - exited and this yield then the yield will not cause the task - to block. */ - portYIELD_WITHIN_API(); - } - } - } - else - { - xTaskResumeAll(); - } - } -} -/*-----------------------------------------------------------*/ - -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) -{ -portTickType xNextExpireTime; - - /* Timers are listed in expiry time order, with the head of the list - referencing the task that will expire first. Obtain the time at which - the timer with the nearest expiry time will expire. If there are no - active timers then just set the next expire time to 0. That will cause - this task to unblock when the tick count overflows, at which point the - timer lists will be switched and the next expiry time can be - re-assessed. */ - *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); - if( *pxListWasEmpty == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - } - else - { - /* Ensure the task unblocks when the tick count rolls over. */ - xNextExpireTime = ( portTickType ) 0U; - } - - return xNextExpireTime; -} -/*-----------------------------------------------------------*/ - -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) -{ -portTickType xTimeNow; -PRIVILEGED_DATA static portTickType xLastTime = ( portTickType ) 0U; - - xTimeNow = xTaskGetTickCount(); - - if( xTimeNow < xLastTime ) - { - prvSwitchTimerLists( xLastTime ); - *pxTimerListsWereSwitched = pdTRUE; - } - else - { - *pxTimerListsWereSwitched = pdFALSE; - } - - xLastTime = xTimeNow; - - return xTimeNow; -} -/*-----------------------------------------------------------*/ - -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) -{ -portBASE_TYPE xProcessTimerNow = pdFALSE; - - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - - if( xNextExpiryTime <= xTimeNow ) - { - /* Has the expiry time elapsed between the command to start/reset a - timer was issued, and the time the command was processed? */ - if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) - { - /* The time between a command being issued and the command being - processed actually exceeds the timers period. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); - } - } - else - { - if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) - { - /* If, since the command was issued, the tick count has overflowed - but the expiry time has not, then the timer must have already passed - its expiry time and should be processed immediately. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - } - - return xProcessTimerNow; -} -/*-----------------------------------------------------------*/ - -static void prvProcessReceivedCommands( void ) -{ -xTIMER_MESSAGE xMessage; -xTIMER *pxTimer; -portBASE_TYPE xTimerListsWereSwitched, xResult; -portTickType xTimeNow; - - /* In this case the xTimerListsWereSwitched parameter is not used, but it - must be present in the function call. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - - while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) - { - pxTimer = xMessage.pxTimer; - - /* Is the timer already in a list of active timers? When the command - is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the - command is to the task rather than to an individual timer. */ - if( pxTimer != NULL ) - { - if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) - { - /* The timer is in a list, remove it. */ - vListRemove( &( pxTimer->xTimerListItem ) ); - } - } - - traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); - - switch( xMessage.xMessageID ) - { - case tmrCOMMAND_START : - /* Start or restart a timer. */ - if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Process it now. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - break; - - case tmrCOMMAND_STOP : - /* The timer has already been removed from the active list. - There is nothing to do here. */ - break; - - case tmrCOMMAND_CHANGE_PERIOD : - pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; - configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); - prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); - break; - - case tmrCOMMAND_DELETE : - /* The timer has already been removed from the active list, - just free up the memory. */ - vPortFree( pxTimer ); - break; - - default : - /* Don't expect to get here. */ - break; - } - } -} -/*-----------------------------------------------------------*/ - -static void prvSwitchTimerLists( portTickType xLastTime ) -{ -portTickType xNextExpireTime, xReloadTime; -xList *pxTemp; -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove compiler warnings if configASSERT() is not defined. */ - ( void ) xLastTime; - - /* The tick count has overflowed. The timer lists must be switched. - If there are any timers still referenced from the current timer list - then they must have expired and should be processed before the lists - are switched. */ - while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - - /* Remove the timer from the list. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - - /* Execute its callback, then send a command to restart the timer if - it is an auto-reload timer. It cannot be restarted here as the lists - have not yet been switched. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* Calculate the reload value, and if the reload value results in - the timer going into the same timer list then it has already expired - and the timer should be re-inserted into the current list so it is - processed again within this loop. Otherwise a command should be sent - to restart the timer to ensure it is only inserted into a list after - the lists have been swapped. */ - xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); - if( xReloadTime > xNextExpireTime ) - { - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - else - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - } - - pxTemp = pxCurrentTimerList; - pxCurrentTimerList = pxOverflowTimerList; - pxOverflowTimerList = pxTemp; -} -/*-----------------------------------------------------------*/ - -static void prvCheckForValidListAndQueue( void ) -{ - /* Check that the list from which active timers are referenced, and the - queue used to communicate with the timer service, have been - initialised. */ - taskENTER_CRITICAL(); - { - if( xTimerQueue == NULL ) - { - vListInitialise( &xActiveTimerList1 ); - vListInitialise( &xActiveTimerList2 ); - pxCurrentTimerList = &xActiveTimerList1; - pxOverflowTimerList = &xActiveTimerList2; - xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); - } - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) -{ -portBASE_TYPE xTimerIsInActiveList; -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - /* Is the timer in the list of active timers? */ - taskENTER_CRITICAL(); - { - /* Checking to see if it is in the NULL list in effect checks to see if - it is referenced from either the current or the overflow timer lists in - one go, but the logic has to be reversed, hence the '!'. */ - xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); - } - taskEXIT_CRITICAL(); - - return xTimerIsInActiveList; -} -/*-----------------------------------------------------------*/ - -void *pvTimerGetTimerID( xTimerHandle xTimer ) -{ -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - return pxTimer->pvTimerID; -} -/*-----------------------------------------------------------*/ - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. If you want to include software timer -functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#endif /* configUSE_TIMERS == 1 */ diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index d3fbe082a..07954d3b2 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -103,9 +103,10 @@ STMUSBINCDIR = $(STMUSBDIR)/inc CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 DOSFSDIR = $(APPLIBDIR)/dosfs MSDDIR = $(APPLIBDIR)/msd -RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSDIR = $(PIOSCOMMON)/Libraries/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include +RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source DOXYGENDIR = ../Doc/Doxygen AHRSBOOTLOADER = ../Bootloaders/AHRS/ AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc @@ -236,8 +237,8 @@ SRC += $(RTOSSRCDIR)/queue.c SRC += $(RTOSSRCDIR)/tasks.c ## RTOS Portable -SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_1.c +SRC += $(RTOSPORTDIR)/portable/GCC/ARM_CM3/port.c +SRC += $(RTOSPORTDIR)/portable/MemMang/heap_1.c # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files @@ -288,7 +289,7 @@ EXTRAINCDIRS += $(DOSFSDIR) EXTRAINCDIRS += $(MSDDIR) EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 +EXTRAINCDIRS += $(RTOSPORTDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) From 715fb65df7df49813a119654256b2eb45df54988 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 7 Oct 2012 09:42:20 -0500 Subject: [PATCH 506/508] OSX Simulation: Start populating the board and fw information This will allow testing the tablet to know what type of UAVOs to expect. Conflicts: flight/Revolution/Makefile.osx --- flight/Revolution/Makefile.osx | 41 +++++++++++----------------------- 1 file changed, 13 insertions(+), 28 deletions(-) diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index 95f1f906e..f9cd77ed8 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -23,6 +23,7 @@ ##### BOARD_NAME=revolution +TCHAIN_PREFIX ?= WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) TOP := $(realpath $(WHEREAMI)/../../) include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -124,8 +125,6 @@ UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python MODNAMES = $(notdir ${MODULES}) -ifndef TESTAPP - ## PyMite files SRC += $(OUTDIR)/pmlib_img.c SRC += $(OUTDIR)/pmlib_nat.c @@ -146,18 +145,10 @@ SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c -else -## TESTCODE -SRC += $(OPTESTS)/test_common.c -SRC += $(OPTESTS)/$(TESTAPP).c -endif -## UAVOBJECTS -ifndef TESTAPP -#include $(UAVOBJSYNTHDIR)/Makefile.inc -include ./UAVObjects.inc +include $(WHEREAMI)/UAVObjects.inc UAVOBJSRCFILENAMES += attitudesimulated UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) @@ -165,7 +156,6 @@ UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAV SRC += $(UAVOBJSRC) CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) -endif ## PIOS Hardware (posix) SRC += $(PIOSPOSIX)/pios_crc.c @@ -411,8 +401,18 @@ MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} +$(OUTDIR)/sim_osx_firmwareinfo.c: $(TOP)/make/templates/firmwareinfotemplate_sim.c + $(V1) python $(TOP)/make/scripts/version-info.py \ + --path=$(TOP) \ + --template=$(TOP)/make/templates/firmwareinfotemplate_sim.c \ + --outfile=$(TOP)/build/sim_osx/sim_osx_firmwareinfo.c \ + --image=$(TOP)/build/fw_revolution/fw_revolution.elf \ + --type=9 \ + --revision=1 \ + --uavodir=$(TOP)/shared/uavobjectdefinition + # List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) $(OUTDIR)/sim_osx_firmwareinfo.c # List of all source files without directory and file-extension. ALLSRCBASE = $(notdir $(basename $(ALLSRC))) @@ -513,21 +513,6 @@ gccversion : @$(CC) --version # @echo $(ALLOBJ) -# Program the device. -ifeq ($(USE_BOOTLOADER), YES) -# Program the device with OP Upload Tool". -program: $(OUTDIR)/$(TARGET).bin - @echo ${quote}Programming with OP Upload Tool${quote} - ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin -else -ifeq ($(FLASH_TOOL),OPENOCD) -# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". -program: $(OUTDIR)/$(TARGET).elf - @echo ${quote}Programming with OPENOCD${quote} - $(OOCD_EXE) $(OOCD_CL) -endif -endif - # Create final output file (.hex) from ELF output file. %.hex: %.elf ## @echo From c0b9d9015d87b8d32f691e5ba98d38c28fff7c1b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 8 Oct 2012 08:21:35 -0500 Subject: [PATCH 507/508] Hack: The OSX sim includes modules slightly differently than the main code so needs an implementation of FirmwareIAPStart() until this is fixed. --- flight/Modules/FirmwareIAP/inc/firmwareiap.h | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/Modules/FirmwareIAP/inc/firmwareiap.h b/flight/Modules/FirmwareIAP/inc/firmwareiap.h index 0266f7450..05d5e518f 100644 --- a/flight/Modules/FirmwareIAP/inc/firmwareiap.h +++ b/flight/Modules/FirmwareIAP/inc/firmwareiap.h @@ -27,6 +27,7 @@ #define FIRMWAREIAP_H int32_t FirmwareIAPInitialize(); +int32_t FirmwareIAPStart() {return 0;}; #endif // FIRMWAREIAP_H From 0c3084b9b15cc60fa12a42a402e91dd9a4008691 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 10 Oct 2012 09:41:44 -0500 Subject: [PATCH 508/508] OPMap: Line got missed in merge --- ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index afccc51e4..8c0f7995f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -222,6 +222,7 @@ private slots: void onMaxUpdateRateActGroup_triggered(QAction *action); void onChangeDefaultLocalAndZoom(); + void on_tbFind_clicked(); void onHomeDoubleClick(HomeItem*); void onOverlayOpacityActGroup_triggered(QAction *action); void on_leFind_returnPressed();