Skip to content

Commit

Permalink
deprecate velctrl msgs, remove old refs to common_msgs, redefine as f…
Browse files Browse the repository at this point in the history
…reyja_msgs
  • Loading branch information
ajshank committed Nov 15, 2020
1 parent 508ecc4 commit 29e87a6
Show file tree
Hide file tree
Showing 13 changed files with 29 additions and 49 deletions.
4 changes: 2 additions & 2 deletions freyja_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(common_msgs)
project(freyja_msgs)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
Expand Down Expand Up @@ -53,7 +53,7 @@ generate_messages(
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES common_msgs
# LIBRARIES freyja_msgs
# CATKIN_DEPENDS geometry_msgs message_generation message_runtime roscpp std_msgs
# DEPENDS system_lib
)
Expand Down
5 changes: 3 additions & 2 deletions freyja_msgs/msg/lqr_ctrl/CtrlCommand.msg
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
# Control commands for the attitude controller.
# Need to translate differently for AscTec HLP/LLP, PX4, AC etc.
# Attitude in radians, thrust in *Newtons*. No scaling!
# ctrl_mode is 8 bits (asctec): [ x x gps height thrust yaw roll pitch ]

# ctrl_mode is:
# 8 bits (asctec): [ x x gps height thrust yaw roll pitch ]
# 8 bits (apm) : [ x x x x x x yawrate ctrlvalid]
float64 roll
float64 pitch
float64 yaw
Expand Down
10 changes: 0 additions & 10 deletions freyja_msgs/msg/lqr_vel_ctrl/ControllerDebug.msg

This file was deleted.

9 changes: 0 additions & 9 deletions freyja_msgs/msg/lqr_vel_ctrl/CtrlCommand.msg

This file was deleted.

1 change: 1 addition & 0 deletions freyja_msgs/msg/state_manager/CurrentState.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
# [pn, pe, pd, vn, ve, vd, roll, pitch, yaw, rrate, prate, yrate, delta_t]
Header header
float64[13] state_vector
uint8 state_valid
11 changes: 4 additions & 7 deletions freyja_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -1,16 +1,13 @@
<?xml version="1.0"?>
<package format="2">
<name>common_msgs</name>
<name>freyja_msgs</name>
<version>0.0.0</version>
<description>The common_msgs package</description>
<description>The freyja_msgs package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="[email protected]">Jane Doe</maintainer> -->
<maintainer email="[email protected]">aj</maintainer>
<maintainer email="[email protected]">aj</maintainer>


<license>TODO</license>
<license>GPLv3</license>


<buildtool_depend>catkin</buildtool_depend>
Expand Down
2 changes: 1 addition & 1 deletion state_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
geometry_msgs
common_msgs
freyja_msgs
sensor_msgs
nav_msgs
)
Expand Down
14 changes: 7 additions & 7 deletions state_manager/include/state_estimator.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,15 +23,15 @@
#include <sensor_msgs/NavSatFix.h>
#include <nav_msgs/Odometry.h>

#include <common_msgs/CurrentState.h>
#include <common_msgs/CurrentStateEst.h>
#include <common_msgs/AsctecData.h>
#include <common_msgs/ControllerDebug.h>
#include <freyja_msgs/CurrentState.h>
#include <freyja_msgs/CurrentStateEst.h>
#include <freyja_msgs/AsctecData.h>
#include <freyja_msgs/ControllerDebug.h>


#include "aj_filter_collection.cpp"

typedef common_msgs::ControllerDebug::ConstPtr LqrInputAccel;
typedef freyja_msgs::ControllerDebug::ConstPtr LqrInputAccel;

#if LQE_INTEGRATOR_ORDER_ == 2
const int nStates = 9;
Expand Down Expand Up @@ -80,7 +80,7 @@ class StateEstimator
std::chrono::duration<double> prop_interval_;

// final ros data published
common_msgs::CurrentStateBiasFree state_msg_;
freyja_msgs::CurrentStateBiasFree state_msg_;

public:
StateEstimator();
Expand All @@ -90,7 +90,7 @@ class StateEstimator

// listen to state information from an external source
ros::Subscriber state_sub_;
void stateUpdatesCallback( const common_msgs::CurrentState::ConstPtr & );
void stateUpdatesCallback( const freyja_msgs::CurrentState::ConstPtr & );

// listen to full control commands (atti + accel) from the controller
ros::Subscriber ctrl_input_sub_;
Expand Down
2 changes: 1 addition & 1 deletion state_manager/include/state_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class StateManager

/* Callback handler for asctec_onboard_data */
ros::Subscriber asctec_data_sub_;
void asctecDataCallback( const common_msgs::AsctecData::ConstPtr & );
void asctecDataCallback( const freyja_msgs::AsctecData::ConstPtr & );

/* Callback handlers for mavros data */
ros::Subscriber mavros_gps_sub_;
Expand Down
4 changes: 2 additions & 2 deletions state_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,14 @@
<description>The state_manager package</description>

<maintainer email="[email protected]">aj</maintainer>
<license>Risky</license>
<license>GPLv3</license>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>common_msgs</build_depend>
<build_depend>freyja_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>nav_msgs</build_depend>

Expand Down
10 changes: 5 additions & 5 deletions state_manager/src/callback_implementations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,14 +74,14 @@ void StateManager::viconCallback( const TFStamped::ConstPtr &msg )
last_yaw_ = yaw;

/* Copy over and publish right away */
common_msgs::CurrentState state_msg;
freyja_msgs::CurrentState state_msg;
state_msg.header.stamp = ros::Time::now();
for( uint8_t idx = 0; idx < STATE_VECTOR_LEN; idx++ )
state_msg.state_vector[idx] = state_vector_[idx];
state_pub_.publish( state_msg );
}

void StateManager::asctecDataCallback( const common_msgs::AsctecData::ConstPtr &msg )
void StateManager::asctecDataCallback( const freyja_msgs::AsctecData::ConstPtr &msg )
{
double time_since = (ros::Time::now() - lastUpdateTime_).toSec();
double x, y, z, vx, vy, vz;
Expand Down Expand Up @@ -145,7 +145,7 @@ void StateManager::asctecDataCallback( const common_msgs::AsctecData::ConstPtr &
last_pd_ = state_vector_[2];

/* Copy over and publish right away */
common_msgs::CurrentState state_msg;
freyja_msgs::CurrentState state_msg;
state_msg.header.stamp = ros::Time::now();
for( uint8_t idx = 0; idx < STATE_VECTOR_LEN; idx++ )
state_msg.state_vector[idx] = state_vector_[idx];
Expand Down Expand Up @@ -185,7 +185,7 @@ void StateManager::mavrosGpsVelCallback( const TwStamped::ConstPtr &msg )

lastUpdateTime_ = ros::Time::now();

common_msgs::CurrentState state_msg;
freyja_msgs::CurrentState state_msg;
state_msg.header.stamp = ros::Time::now();
for( uint8_t idx = 0; idx < STATE_VECTOR_LEN; idx++ )
state_msg.state_vector[idx] = state_vector_[idx];
Expand Down Expand Up @@ -253,7 +253,7 @@ void StateManager::cameraUpdatesCallback( const CameraOdom::ConstPtr &msg )
state_vector_[8] = yaw;

// publish away!
common_msgs::CurrentState state_msg;
freyja_msgs::CurrentState state_msg;
state_msg.header.stamp = ros::Time::now();
for( uint8_t idx = 0; idx < STATE_VECTOR_LEN; idx++ )
state_msg.state_vector[idx] = state_vector_[idx];
Expand Down
4 changes: 2 additions & 2 deletions state_manager/src/state_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ StateEstimator::StateEstimator() : nh_(), priv_nh_("~")
std::string output_topic;
priv_nh_.param( "output_topic", output_topic, std::string("/current_state_estimate") );
// for when all is said and done
state_pub_ = nh_.advertise <common_msgs::CurrentStateBiasFree>
state_pub_ = nh_.advertise <freyja_msgs::CurrentStateBiasFree>
( output_topic, 1, true );

int estimator_rate_default = 70;
Expand Down Expand Up @@ -261,7 +261,7 @@ void StateEstimator::medianFilter()
*/
}

void StateEstimator::stateUpdatesCallback( const common_msgs::CurrentState::ConstPtr & msg )
void StateEstimator::stateUpdatesCallback( const freyja_msgs::CurrentState::ConstPtr & msg )
{

// no need to mutexify this, since measurement_z_ is only used in update function
Expand Down
2 changes: 1 addition & 1 deletion state_manager/src/state_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ StateManager::StateManager() : nh_(), priv_nh_("~")


/* Announce state publisher */
state_pub_ = nh_.advertise <common_msgs::CurrentState>
state_pub_ = nh_.advertise <freyja_msgs::CurrentState>
( "current_state", 1, true );

/* Instantiate filters. Useful for vicon. Autopilots have their own filters */
Expand Down

0 comments on commit 29e87a6

Please sign in to comment.