Skip to content
This repository has been archived by the owner on Nov 22, 2023. It is now read-only.

Commit

Permalink
Move OperationMode msg and GetOperationMode srv to pilz_msgs (#470)
Browse files Browse the repository at this point in the history
  • Loading branch information
martiniil authored Nov 23, 2020
1 parent 84bae42 commit 94bee44
Show file tree
Hide file tree
Showing 23 changed files with 67 additions and 97 deletions.
2 changes: 1 addition & 1 deletion pilz_status_indicator_rqt/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@

<buildtool_depend>catkin</buildtool_depend>

<exec_depend>pilz_msgs</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>rqt_gui</exec_depend>
<exec_depend>rqt_gui_py</exec_depend>
<exec_depend>prbt_hardware_support</exec_depend>
<exec_depend>std_msgs</exec_depend>

<build_depend>rospy</build_depend>
Expand Down
2 changes: 1 addition & 1 deletion pilz_status_indicator_rqt/scripts/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

import rospy
from numpy import arange
from prbt_hardware_support.msg import OperationModes
from pilz_msgs.msg import OperationModes
from std_msgs.msg import Bool, Float64

from pilz_status_indicator_rqt.status_indicator import (TOPIC_STATE_HW,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
import rospy
from pilz_status_indicator_rqt.status_indicator_widget import \
PilzStatusIndicatorWidget
from prbt_hardware_support.msg import OperationModes
from pilz_msgs.msg import OperationModes
from qt_gui.plugin import Plugin
from std_msgs.msg import Bool, Float64

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

import rospkg
import rospy
from prbt_hardware_support.msg import OperationModes
from pilz_msgs.msg import OperationModes
from python_qt_binding import loadUi
from python_qt_binding.QtGui import QPixmap
from python_qt_binding.QtWidgets import QWidget
Expand Down Expand Up @@ -82,7 +82,7 @@ def set_operation_mode(self, mode, _qpixmap_class=QPixmap):
both the shown image and the text beneath it.
:param mode: The mode to be set of type
`prbt_hardware_support.msg.OperationModes`.
`pilz_msgs.msg.OperationModes`.
:param _qpixmap_class: (Internal use only)"""
if mode == OperationModes.AUTO:
icon_name = 'auto'
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

import rospy
from mock import ANY, MagicMock, Mock, call, patch
from prbt_hardware_support.msg import OperationModes
from pilz_msgs.msg import OperationModes
from python_qt_binding.QtCore import QObject
from qt_gui.plugin import Plugin
from std_msgs.msg import Bool, Float64
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
import rospkg
import rospy
from mock import ANY, MagicMock, create_autospec
from prbt_hardware_support.msg import OperationModes
from pilz_msgs.msg import OperationModes
from PyQt5.QtGui import QPixmap
from python_qt_binding.QtWidgets import QApplication, QMainWindow

Expand Down
6 changes: 0 additions & 6 deletions prbt_hardware_support/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,12 @@ add_message_files(
BrakeTestErrorCodes.msg
ModbusMsgInStamped.msg
ModbusRegisterBlock.msg
OperationModes.msg
)

# action generation
add_service_files(
FILES
BrakeTest.srv
GetOperationMode.srv
SendBrakeTestResult.srv
WriteModbusRegister.srv
)
Expand Down Expand Up @@ -546,10 +544,6 @@ if(CATKIN_ENABLE_TESTING)
"*/WriteModbusRegister.h"
"*/WriteModbusRegisterRequest.h"
"*/WriteModbusRegisterResponse.h"
"*/GetOperationMode.h"
"*/GetOperationModeRequest.h"
"*/GetOperationModeResponse.h"
"*/OperationModes.h"
"*/SendBrakeTestResult.h"
"*/SendBrakeTestResultRequest.h"
"*/SendBrakeTestResultResponse.h"
Expand Down
2 changes: 1 addition & 1 deletion prbt_hardware_support/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ The ``ModbusAdapterOperationModeNode`` publishes the active operation mode
on the topic `/prbt/operation_mode` everytime it changes and offers
the `/get_operation_mode` service for accessing the active operation mode.

Use `rosmsg show prbt_hardware_support/OperationModes` to see the definition
Use `rosmsg show pilz_msgs/OperationModes` to see the definition
of each value.

## OperationModeSetupExecutorNode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@

#include <ros/ros.h>

#include <prbt_hardware_support/GetOperationMode.h>
#include <prbt_hardware_support/OperationModes.h>
#include <pilz_msgs/GetOperationMode.h>
#include <pilz_msgs/OperationModes.h>

namespace prbt_hardware_support
{
Expand All @@ -40,19 +40,19 @@ class AdapterOperationMode
/**
* @brief Stores the operation mode and publishes it, if it has changed.
*/
void updateOperationMode(const OperationModes& mode);
void updateOperationMode(const pilz_msgs::OperationModes& mode);

private:
/**
* @brief Initializes the operation mode service.
*/
void initOperationModeService();

bool getOperationMode(GetOperationMode::Request& req, GetOperationMode::Response& res);
bool getOperationMode(pilz_msgs::GetOperationMode::Request& req, pilz_msgs::GetOperationMode::Response& res);

private:
//! Store the current operation mode according to OperationModes.msg
OperationModes op_mode_;
pilz_msgs::OperationModes op_mode_;

//! Protects read/write of the operation mode
std::mutex op_mode_mutex_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
#define GET_OPERATION_MODE_FUNC_DECL_H

#include <functional>
#include <prbt_hardware_support/OperationModes.h>
#include <pilz_msgs/OperationModes.h>

namespace prbt_hardware_support
{
using GetOpModeFunc = std::function<OperationModes()>;
using GetOpModeFunc = std::function<pilz_msgs::OperationModes()>;
}

#endif // GET_OPERATION_MODE_FUNC_DECL_H
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@

#include <ros/ros.h>

#include <pilz_msgs/OperationModes.h>

#include <prbt_hardware_support/adapter_operation_mode.h>
#include <prbt_hardware_support/modbus_msg_operation_mode_wrapper.h>
#include <prbt_hardware_support/ModbusMsgInStamped.h>
Expand Down Expand Up @@ -55,7 +57,7 @@ class ModbusAdapterOperationMode : public AdapterOperationMode
void modbusMsgCallback(const ModbusMsgInStampedConstPtr& msg_raw);

private:
static OperationModes createUnknownOperationMode();
static pilz_msgs::OperationModes createUnknownOperationMode();

private:
const ModbusApiSpec api_spec_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,9 @@
#ifndef MODBUS_MSG_OPERATION_MODE_WRAPPER_H
#define MODBUS_MSG_OPERATION_MODE_WRAPPER_H

#include <pilz_msgs/OperationModes.h>

#include <prbt_hardware_support/ModbusMsgInStamped.h>
#include <prbt_hardware_support/OperationModes.h>
#include <prbt_hardware_support/modbus_api_definitions.h>
#include <prbt_hardware_support/modbus_api_spec.h>
#include <prbt_hardware_support/modbus_msg_wrapper.h>
Expand Down Expand Up @@ -57,7 +58,7 @@ class ModbusMsgOperationModeWrapper : public ModbusMsgWrapper
/**
* @returns the operation mode and the corresponding time stamp.
*/
OperationModes getTimeStampedOperationMode() const;
pilz_msgs::OperationModes getTimeStampedOperationMode() const;

private:
/**
Expand All @@ -84,21 +85,21 @@ inline int8_t ModbusMsgOperationModeWrapper::getOperationMode() const
switch (getRegister(getApiSpec().getRegisterDefinition(modbus_api_spec::OPERATION_MODE)))
{
case MODBUS_OPERATION_MODE_NONE:
return OperationModes::UNKNOWN;
return pilz_msgs::OperationModes::UNKNOWN;
case MODBUS_OPERATION_MODE_T1:
return OperationModes::T1;
return pilz_msgs::OperationModes::T1;
case MODBUS_OPERATION_MODE_T2:
return OperationModes::T2;
return pilz_msgs::OperationModes::T2;
case MODBUS_OPERATION_MODE_AUTO:
return OperationModes::AUTO;
return pilz_msgs::OperationModes::AUTO;
default:
return OperationModes::UNKNOWN;
return pilz_msgs::OperationModes::UNKNOWN;
}
}

inline OperationModes ModbusMsgOperationModeWrapper::getTimeStampedOperationMode() const
inline pilz_msgs::OperationModes ModbusMsgOperationModeWrapper::getTimeStampedOperationMode() const
{
OperationModes op_mode;
pilz_msgs::OperationModes op_mode;
op_mode.time_stamp = getTimeStamp();
op_mode.value = getOperationMode();
return op_mode;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include <ros/ros.h>

#include <pilz_msgs/GetSpeedOverride.h>
#include <pilz_msgs/OperationModes.h>

#include <prbt_hardware_support/OperationModes.h>
#include <prbt_hardware_support/monitor_cartesian_speed_func_decl.h>
#include <prbt_hardware_support/get_operation_mode_func_decl.h>

Expand All @@ -48,7 +48,7 @@ class OperationModeSetupExecutor
/**
* @brief Function to be called whenever a new operation mode is set.
*/
void updateOperationMode(const OperationModes& operation_mode);
void updateOperationMode(const pilz_msgs::OperationModes& operation_mode);

bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request& /*req*/, pilz_msgs::GetSpeedOverride::Response& response);

Expand Down
23 changes: 0 additions & 23 deletions prbt_hardware_support/msg/OperationModes.msg

This file was deleted.

11 changes: 6 additions & 5 deletions prbt_hardware_support/src/adapter_operation_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ static constexpr int DEFAULT_QUEUE_SIZE{ 10 };
AdapterOperationMode::AdapterOperationMode(ros::NodeHandle& nh) : nh_(nh)
{
op_mode_.time_stamp = ros::Time::now();
op_mode_.value = OperationModes::UNKNOWN;
op_mode_.value = pilz_msgs::OperationModes::UNKNOWN;

operation_mode_pub_ = nh_.advertise<OperationModes>(TOPIC_OPERATION_MODE, DEFAULT_QUEUE_SIZE,
true); // latched publisher
operation_mode_pub_ = nh_.advertise<pilz_msgs::OperationModes>(TOPIC_OPERATION_MODE, DEFAULT_QUEUE_SIZE,
true); // latched publisher
// publish initial operation mode before first switch
operation_mode_pub_.publish(op_mode_);

Expand All @@ -43,7 +43,7 @@ void AdapterOperationMode::initOperationModeService()
nh_.advertiseService(SERVICE_NAME_GET_OPERATION_MODE, &AdapterOperationMode::getOperationMode, this);
}

void AdapterOperationMode::updateOperationMode(const OperationModes& new_op_mode)
void AdapterOperationMode::updateOperationMode(const pilz_msgs::OperationModes& new_op_mode)
{
std::unique_lock<std::mutex> lock(op_mode_mutex_);
const int8_t last_op_mode_value{ op_mode_.value };
Expand All @@ -58,7 +58,8 @@ void AdapterOperationMode::updateOperationMode(const OperationModes& new_op_mode
}
}

bool AdapterOperationMode::getOperationMode(GetOperationMode::Request& /*req*/, GetOperationMode::Response& res)
bool AdapterOperationMode::getOperationMode(pilz_msgs::GetOperationMode::Request& /*req*/,
pilz_msgs::GetOperationMode::Response& res)
{
std::lock_guard<std::mutex> lock(op_mode_mutex_);
res.mode = op_mode_;
Expand Down
6 changes: 3 additions & 3 deletions prbt_hardware_support/src/modbus_adapter_operation_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ ModbusAdapterOperationMode::ModbusAdapterOperationMode(ros::NodeHandle& nh, cons
{
}

OperationModes ModbusAdapterOperationMode::createUnknownOperationMode()
pilz_msgs::OperationModes ModbusAdapterOperationMode::createUnknownOperationMode()
{
OperationModes op_mode;
pilz_msgs::OperationModes op_mode;
op_mode.time_stamp = ros::Time::now();
op_mode.value = OperationModes::UNKNOWN;
op_mode.value = pilz_msgs::OperationModes::UNKNOWN;
return op_mode;
}

Expand Down
6 changes: 3 additions & 3 deletions prbt_hardware_support/src/operation_mode_setup_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ OperationModeSetupExecutor::OperationModeSetupExecutor(const MonitorCartesianSpe
{
}

void OperationModeSetupExecutor::updateOperationMode(const OperationModes& operation_mode)
void OperationModeSetupExecutor::updateOperationMode(const pilz_msgs::OperationModes& operation_mode)
{
ROS_DEBUG("updateOperationMode: %d", operation_mode.value);
if (operation_mode.time_stamp <= time_stamp_last_op_mode_)
Expand All @@ -38,11 +38,11 @@ void OperationModeSetupExecutor::updateOperationMode(const OperationModes& opera
boost::optional<bool> monitor_cartesian_speed{ boost::none };
switch (operation_mode.value)
{
case OperationModes::T1:
case pilz_msgs::OperationModes::T1:
monitor_cartesian_speed = true;
speed_override_ = 0.1;
break;
case OperationModes::AUTO:
case pilz_msgs::OperationModes::AUTO:
monitor_cartesian_speed = false;
speed_override_ = 1.0;
break;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,13 @@

#include <std_srvs/SetBool.h>

#include <pilz_msgs/GetOperationMode.h>

#include <pilz_utils/get_param.h>
#include <pilz_utils/wait_for_service.h>

#include <prbt_hardware_support/operation_mode_setup_executor.h>
#include <prbt_hardware_support/monitor_cartesian_speed_func_decl.h>
#include <prbt_hardware_support/GetOperationMode.h>
#include <prbt_hardware_support/get_operation_mode_func_decl.h>
#include <prbt_hardware_support/operation_mode_setup_executor_node_service_calls.h>

Expand Down
18 changes: 0 additions & 18 deletions prbt_hardware_support/srv/GetOperationMode.srv

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,11 @@
#include <ros/ros.h>
#include <modbus/modbus.h>

#include <pilz_msgs/OperationModes.h>

#include <pilz_testutils/async_test.h>

#include <prbt_hardware_support/pilz_modbus_server_mock.h>
#include <prbt_hardware_support/OperationModes.h>
#include <prbt_hardware_support/ros_test_helper.h>
#include <prbt_hardware_support/modbus_api_definitions.h>
#include <prbt_hardware_support/modbus_api_spec.h>
Expand All @@ -52,7 +53,7 @@ class OperationModeSubscriberMock
*/
void initialize();

MOCK_METHOD1(callback, void(const OperationModesConstPtr& msg));
MOCK_METHOD1(callback, void(const pilz_msgs::OperationModesConstPtr& msg));

protected:
ros::NodeHandle nh_;
Expand All @@ -71,6 +72,9 @@ void OperationModeSubscriberMock::initialize()
*/
class OperationModeIntegrationTest : public testing::Test, public testing::AsyncTest
{
protected:
using OperationModes = pilz_msgs::OperationModes;

protected:
ros::NodeHandle nh_;
ros::NodeHandle nh_priv_{ "~" };
Expand Down
Loading

0 comments on commit 94bee44

Please sign in to comment.