Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions .github/workflows/package.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,16 +9,20 @@ jobs:
strategy:
matrix:
os: [ubuntu-18.04, [self-hosted,linux,arm64]]
fail-fast: true
steps:
- name: Remove File
uses: JesseTG/rm@v1.0.0
with:
path: '*'
- uses: actions/checkout@v1
- name: Package
id: package
uses: AutoModality/action-package-debian-ros@v1.3.0
uses: AutoModality/action-package-debian-ros@v1.3.2
with:
branch: ${{ github.event.pull_request.head.ref }}
pull-request-number: ${{ github.event.number }}
build-number: ${{ github.run_number }}
release-repo-entitlement: ${{ secrets.CLOUDSMITH_READ_RELEASE_ENTITLEMENT }}
- name: The generated package
run: echo "The artifact is ${{ steps.package.outputs.artifact-path }}"
- name: Deploy
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/release.yml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ jobs:
strategy:
matrix:
os: [ubuntu-18.04, [self-hosted,linux,arm64]]
fail-fast: true
needs: release
name: Package if released
steps:
Expand Down Expand Up @@ -68,6 +67,7 @@ jobs:
uses: AutoModality/action-package-debian-ros@v1.3.2
with:
version: ${{ steps.version.outputs.value }}
release-repo-entitlement: ${{ secrets.CLOUDSMITH_READ_RELEASE_ENTITLEMENT }}
- name: Deploy if published
if: steps.published.outputs.value == 'true'
id: deploy
Expand Down
5 changes: 4 additions & 1 deletion .github/workflows/story.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,10 @@ jobs:
steps:
- uses: actions/checkout@v1
- name: Package
uses: AutoModality/action-package-debian-ros@v1.3.0
uses: AutoModality/action-package-debian-ros@v1.3.2
with:
dev-repo-entitlement: ${{ secrets.CLOUDSMITH_READ_DEV_ENTITLEMENT }}
release-repo-entitlement: ${{ secrets.CLOUDSMITH_READ_RELEASE_ENTITLEMENT }}



41 changes: 18 additions & 23 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,35 +2,16 @@ cmake_minimum_required(VERSION 2.8.3)
project(am_utils)

find_package(catkin REQUIRED COMPONENTS
message_generation
geometry_msgs
nav_msgs
genmsg
std_msgs
sensor_msgs
rosconsole
rostime
brain_box_msgs
)

add_message_files(
DIRECTORY msg
FILES
Latency_Image.msg
Latency_LaserScan.msg
Latency_Odometry.msg
Latency_PointCloud.msg
Latency_PointCloud2.msg
Latency_PoseStamped.msg
Latency_PoseWithCovarianceStamped.msg
Latency_TwistStamped.msg
Latency_TwistWithCovarianceStamped.msg
Latency.msg
Latency_String.msg
LatencyHeader.msg
LatencyTest.msg
DelayStats.msg
)

generate_messages( DEPENDENCIES std_msgs nav_msgs geometry_msgs sensor_msgs)

set(CMAKE_CXX_FLAGS "-std=c++0x ${CMAKE_CXX_FLAGS}")
Expand All @@ -39,11 +20,11 @@ catkin_package(
INCLUDE_DIRS include include/am_utils
LIBRARIES am_utils
CATKIN_DEPENDS
message_runtime
geometry_msgs
nav_msgs
std_msgs
sensor_msgs
brain_box_msgs
)

include_directories(
Expand All @@ -55,10 +36,24 @@ install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

add_library(am_utils
src/latency_wrapper.cpp src/am_statistics.cpp src/topics.cpp src/cansocket.cpp src/am_onlinestatistics.cpp
src/am_bag_utils.cpp
src/am_network_utils.cpp
src/am_onlinestatistics.cpp
src/am_operator_utils.cpp
src/am_statistics.cpp
src/cansocket.cpp
src/fcu_mode_type.cpp
src/flightplan_type.cpp
src/latency_wrapper.cpp
src/message_util.cpp
src/mission_cmd_type.cpp
src/operator_msg_type.cpp
src/topics.cpp
)

target_link_libraries(am_utils ${catkin_LIBRARIES})
add_dependencies(am_utils am_utils_generate_messages_cpp)

add_dependencies(am_utils brain_box_msgs_generate_messages_cpp)

install(TARGETS am_utils
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
4 changes: 2 additions & 2 deletions debian/control
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@ Source: ros-kinetic-am-utils
Section: misc
Priority: extra
Maintainer: info <info@automodality.com>
Build-Depends: debhelper (>= 9.0.0), ros-kinetic-catkin, ros-kinetic-geometry-msgs, ros-kinetic-message-generation, ros-kinetic-nav-msgs, ros-kinetic-rosconsole, ros-kinetic-roscpp, ros-kinetic-rostime, ros-kinetic-sensor-msgs, ros-kinetic-std-msgs
Build-Depends: debhelper (>= 9.0.0), ros-kinetic-catkin, ros-kinetic-geometry-msgs, ros-kinetic-message-generation, ros-kinetic-nav-msgs, ros-kinetic-rosconsole, ros-kinetic-roscpp, ros-kinetic-rostime, ros-kinetic-sensor-msgs, ros-kinetic-std-msgs, ros-kinetic-am-msgs
Homepage: https://github.com/AutoModality/am-utils
Standards-Version: 3.9.2

Package: ros-kinetic-am-utils
Architecture: any
Depends: ${shlibs:Depends}, ${misc:Depends}, ros-kinetic-geometry-msgs, ros-kinetic-message-runtime, ros-kinetic-nav-msgs, ros-kinetic-rosconsole, ros-kinetic-roscpp, ros-kinetic-rostime, ros-kinetic-sensor-msgs, ros-kinetic-std-msgs
Depends: ${shlibs:Depends}, ${misc:Depends}, ros-kinetic-geometry-msgs, ros-kinetic-message-runtime, ros-kinetic-nav-msgs, ros-kinetic-rosconsole, ros-kinetic-roscpp, ros-kinetic-rostime, ros-kinetic-sensor-msgs, ros-kinetic-std-msgs, ros-kinetic-am-msgs
Description: The am utils package
22 changes: 22 additions & 0 deletions include/am_utils/am_bag_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/*
* am_bag_utils.cpp
*
* Created on: Sep 3, 2015
* Author: dan
*/

#ifndef BRAIN_BOX_MSGS_INCLUDE_BRAIN_BOX_MSGS_AM_BAG_UTILS_CPP_
#define BRAIN_BOX_MSGS_INCLUDE_BRAIN_BOX_MSGS_AM_BAG_UTILS_CPP_

#include <ros/ros.h>

namespace brain_box {

class AMBagUtils {
public:
static std::string getFileName();
};

} /* namespace brain_box */

#endif /* BRAIN_BOX_MSGS_INCLUDE_BRAIN_BOX_MSGS_AM_BAG_UTILS_CPP_ */
29 changes: 29 additions & 0 deletions include/am_utils/am_network_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
/*
* am_network_utils.h
*
* Created on: Jun 2, 2015
* Author: dan
*/

#ifndef BRAIN_BOX_MSGS_SRC_AM_NETWORK_UTILS_H_
#define BRAIN_BOX_MSGS_SRC_AM_NETWORK_UTILS_H_

#include <sys/socket.h>

namespace brain_box {

class AMNetworkUtils {
public:
AMNetworkUtils();
virtual ~AMNetworkUtils();
static void *get_in_addr(struct sockaddr *sa);
static void printSource(struct sockaddr_storage their_addr, socklen_t addr_len, long bytesReceived);
static int openIncomingSocket(const char *name, const char *port);
static int openOutgoingSocket(const char *name, const char *hostname, const char *port, struct addrinfo &addr);
static void getMacAddress(std::string channel, std::string &macAddress);
static void closeSocket(int sockfp);
};

} /* namespace brain_box */

#endif /* BRAIN_BOX_MSGS_SRC_AM_NETWORK_UTILS_H_ */
4 changes: 2 additions & 2 deletions include/am_utils/am_onlinestatistics.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <math.h> /* pow */
#include <vector>
#include <list>
#include "am_utils/DelayStats.h"
#include <brain_box_msgs/DelayStats.h>

namespace am {

Expand All @@ -17,7 +17,7 @@ class OnlineStatistics {
void addData( double val );
void setSize( size_t N );
void insertion_sort(std::vector<double>& ary);
void setDelayStats( am_utils::DelayStats &msg );
void setDelayStats( brain_box_msgs::DelayStats &msg );
inline double getMean() const {return mean_;}
inline double getVariance() const {return var_;}
inline double getMin() const {return ary_.front();}
Expand Down
21 changes: 21 additions & 0 deletions include/am_utils/am_operator_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
/*
* amoperatorutils.h
*
* Created on: Jun 8, 2015
* Author: dan
*/

#ifndef BRAIN_BOX_MSGS_SRC_AMOPERATORUTILS_H_
#define BRAIN_BOX_MSGS_SRC_AMOPERATORUTILS_H_

namespace brain_box {

class AMOperatorUtils {
public:
static void changemode(int dir);
static int kbhit (void);
};

} /* namespace brain_box */

#endif /* BRAIN_BOX_MSGS_SRC_AMOPERATORUTILS_H_ */
4 changes: 2 additions & 2 deletions include/am_utils/am_statistics.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include <geometry_msgs/Vector3Stamped.h>
#include <iostream>
#include <string>
#include <am_utils/Latency.h>
#include <brain_box_msgs/Latency.h>

namespace am
{
Expand All @@ -27,7 +27,7 @@ class Statistics

void setVector(geometry_msgs::Vector3Stamped& vec);
void setVector(geometry_msgs::Vector3Stamped& vec, ros::Time t);
void setLatency(am_utils::Latency& latency);
void setLatency(brain_box_msgs::Latency& latency);

void addData(double data_point);

Expand Down
38 changes: 38 additions & 0 deletions include/am_utils/fcu_mode_type.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
* fcu_mode_type.h
*
* Created on: Nov 25, 2015
* Author: ubuntu
*/

#ifndef VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FCU_MODE_TYPE_H_
#define VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FCU_MODE_TYPE_H_

#include <string>
#include <map>

enum class FCU_MODE {
MANUAL=0,
ACRO=1,
ALTCTL=2,
POSCTL=3,
OFFBOARD=4,
STABILIZED=5,
AUTO_MISSION=6,
AUTO_LOITER=7,
AUTO_RTL=8,
AUTO_LAND=9,
AUTO_RTGS=10,
AUTO_READY=11,
AUTO_TAKEOFF=12,
UNKNOWN=13,
};

extern std::map<FCU_MODE, std::string> mode_2_px4;
extern std::map<std::string, FCU_MODE> px4_2_mode;

#define MODE_TO_PX4(m) mode_2_px4[m]
#define PX4_TO_MODE(p) px4_2_mode[p]
#define PX4_TO_MODE_MSG(p) (static_cast<unsigned int>(px4_2_mode[p]))

#endif /* VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FCU_MODE_TYPE_H_ */
41 changes: 41 additions & 0 deletions include/am_utils/flightplan_type.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* flightplan_type.h
*
* Created on: Nov 24, 2015
* Author: ubuntu
*/

#ifndef VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FLIGHTPLAN_TYPE_H_
#define VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FLIGHTPLAN_TYPE_H_

#include <string>

// From the VxFlightPlan.srv file:
//# key="FP_LOAD" value="id" load the enclosed flight plan and give it id
//# key="FP_LOAD_JSON_FILE value="file name" load json flight plan from file
//# key="FP_LOAD_PX4_FILE value="file name" load PX4 flight plan from file
//# key="FP_DELETE" value="id" delete flight plan with id
//# key="FP_EXECUTE" value="id" execute flight plan with id
//# key="FP_ABORT" value="" abort currently executing flight plan
//# key="FP_PAUSE" value="" pause currently executing flight plan

/**
* Defines for the commands used in VxFlightPlan service requests
*/

enum class FP_CMD { FP_LOAD=0,
FP_LOAD_JSON_FILE,
FP_LOAD_PX4_FILE,
FP_DELETE,
FP_LOAD_FCU,
FP_START,
FP_ABORT,
FP_PAUSE,
};

extern std::string FP_CMD_KEY[];

#define FP_KEY(k) FP_CMD_KEY[static_cast<int>(k)]


#endif /* VISBOX_PACKAGES_COMMON_MESSAGES_INCLUDE_BRAIN_BOX_MSGS_FLIGHTPLAN_TYPE_H_ */
Loading