Skip to content

Commit

Permalink
Merge pull request #60 from jhu-lcsr-forks/hydro-devel-merged
Browse files Browse the repository at this point in the history
Fixes minus ldeployer
  • Loading branch information
jbohren committed Feb 9, 2015
2 parents 8a53d09 + 7ad3b66 commit 1f54dca
Show file tree
Hide file tree
Showing 25 changed files with 151 additions and 100 deletions.
3 changes: 2 additions & 1 deletion rtt_dynamic_reconfigure/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,9 @@ catkin_package(
)

include_directories(
include/orocos
BEFORE
${catkin_INCLUDE_DIRS}
include/orocos
)

orocos_library(rtt_dynamic_reconfigure src/auto_config.cpp)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ namespace rtt_dynamic_reconfigure {

template <>
struct Updater<AutoConfig> {
static bool propertiesFromConfig(AutoConfig &config, uint32_t, RTT::PropertyBag &bag) { RTT::refreshProperties(bag, config); }
static bool configFromProperties(AutoConfig &config, const RTT::PropertyBag &bag) { RTT::updateProperties(config, bag); }
static bool propertiesFromConfig(AutoConfig &config, uint32_t, RTT::PropertyBag &bag) { return RTT::refreshProperties(bag, config); }
static bool configFromProperties(AutoConfig &config, const RTT::PropertyBag &bag) { return RTT::updateProperties(config, bag); }
};

template <>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <rtt/OperationCaller.hpp>

#include <rtt/internal/DataSources.hpp>
#include <rtt/internal/GlobalEngine.hpp>

#include <ros/ros.h>

Expand Down Expand Up @@ -530,6 +531,10 @@ class Server : public RTT::Service
notify_callback_ = getOwner()->provides()->getLocalOperation("notifyPropertiesUpdate");
}

// update_callback_ and notify_callback_ are called from the ROS spinner thread -> set GlobalEngine as caller engine
update_callback_.setCaller(RTT::internal::GlobalEngine::Instance());
notify_callback_.setCaller(RTT::internal::GlobalEngine::Instance());

// refresh once
refresh();
}
Expand Down Expand Up @@ -636,10 +641,6 @@ bool getProperty(const std::string &name, const RTT::PropertyBag &bag, ValueType

} // namespace rtt_dynamic_reconfigure

#include <rtt/plugin/ServicePlugin.hpp>
//#define RTT_DYNAMIC_RECONFIGURE_SERVICE_PLUGIN(CONFIG, NAME) \
// ORO_SERVICE_NAMED_PLUGIN(rtt_dynamic_reconfigure::Server<CONFIG>, NAME)

#define RTT_DYNAMIC_RECONFIGURE_SERVICE_PLUGIN(CONFIG, NAME) \
extern "C" {\
RTT_EXPORT bool loadRTTPlugin(RTT::TaskContext* tc); \
Expand Down
13 changes: 2 additions & 11 deletions rtt_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,17 +60,8 @@ orocos_generate_package(
DEPENDS rostime
)

install(PROGRAMS
scripts/rtt-upgrade-2.5
# Wrapper scripts
scripts/deployer
scripts/orocreate-pkg
scripts/orogen
scripts/orogen-unregister
scripts/rttlua
scripts/rttlua-tlsf
scripts/rttscript
scripts/typegen
install(DIRECTORY scripts/
USE_SOURCE_PERMISSIONS
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
Expand Down
1 change: 1 addition & 0 deletions rtt_ros_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ find_package(catkin REQUIRED COMPONENTS message_generation std_msgs)
## Generate services in the 'srv' folder
add_service_files(
FILES
Eval.srv
RunScript.srv
GetPeerList.srv
)
Expand Down
3 changes: 3 additions & 0 deletions rtt_ros_msgs/srv/Eval.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
string code
---
bool success
1 change: 0 additions & 1 deletion rtt_roscomm/rtt_roscomm_pkg_template/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

</description>
<maintainer email="[email protected]">Orocos Developers</maintainer>
<author>create_rtt_msgs</author>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
2 changes: 1 addition & 1 deletion rtt_rosdeployment/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ include_directories(${catkin_INCLUDE_DIRS})
orocos_use_package(ocl-deployment)

orocos_plugin(rtt_rosdeployment src/rtt_rosdeployment_service.cpp)
target_link_libraries(rtt_rosdeployment ${catkin_LIBRARIES})
target_link_libraries(rtt_rosdeployment ${catkin_LIBRARIES} ${OROCOS-RTT_RTT-SCRIPTING_LIBRARY})

orocos_generate_package(
DEPENDS rtt_ros_msgs
Expand Down
5 changes: 4 additions & 1 deletion rtt_rosdeployment/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,10 @@
<export>
<rtt_ros>
<plugin_depend>rtt_rosnode</plugin_depend>
<plugin_depend>rtt_ros_msgs</plugin_depend>
<!--
rtt_ros_msgs is not an RTT plugin
<plugin_depend>rtt_ros_msgs</plugin_depend>
-->
</rtt_ros>
</export>
</package>
21 changes: 21 additions & 0 deletions rtt_rosdeployment/src/rtt_rosdeployment_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,9 @@
#include <rtt/plugin/Plugin.hpp>
#include <rtt/plugin/ServicePlugin.hpp>
#include <rtt/internal/GlobalService.hpp>
#include <rtt/scripting/Scripting.hpp>

#include <rtt_ros_msgs/Eval.h>
#include <rtt_ros_msgs/RunScript.h>
#include <rtt_ros_msgs/GetPeerList.h>

Expand All @@ -24,16 +26,23 @@ class ROSDeploymentService : public RTT::Service

ros::NodeHandle nh_;

ros::ServiceServer eval_service_;
ros::ServiceServer run_script_service_;
ros::ServiceServer get_peer_list_service_;

bool eval_cb(
rtt_ros_msgs::Eval::Request& request,
rtt_ros_msgs::Eval::Response& response);

bool run_script_cb(
rtt_ros_msgs::RunScript::Request& request,
rtt_ros_msgs::RunScript::Response& response);

bool get_peer_list_cb(
rtt_ros_msgs::GetPeerList::Request& request,
rtt_ros_msgs::GetPeerList::Response& response);

RTT::OperationCaller<bool(std::string const&)> eval_;
};


Expand All @@ -44,13 +53,25 @@ ROSDeploymentService::ROSDeploymentService(OCL::DeploymentComponent* deployer) :
{
if(deployer_) {
// Create services
eval_service_ = nh_.advertiseService("eval",&ROSDeploymentService::eval_cb,this);
run_script_service_ = nh_.advertiseService("run_script",&ROSDeploymentService::run_script_cb,this);
get_peer_list_service_ = nh_.advertiseService("get_peer_list",&ROSDeploymentService::get_peer_list_cb,this);

eval_ = deployer_->getProvider<RTT::Scripting>("scripting")->eval;
} else {
RTT::log(RTT::Error) << "Attempted to load the rosdeployment service on a TaskContext which is not an OCL::DeploymentComponent. No ROS services will be advertised." << RTT::endlog();
}
}

bool ROSDeploymentService::eval_cb(
rtt_ros_msgs::Eval::Request& request,
rtt_ros_msgs::Eval::Response& response)
{
if (!eval_.ready()) return false;
response.success = eval_(request.code);
return true;
}

bool ROSDeploymentService::run_script_cb(
rtt_ros_msgs::RunScript::Request& request,
rtt_ros_msgs::RunScript::Response& response)
Expand Down
72 changes: 45 additions & 27 deletions rtt_rosparam/src/rtt_rosparam_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@
#include <rtt/plugin/ServicePlugin.hpp>
#include <rtt/types/PropertyDecomposition.hpp>

#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/is_convertible.hpp>

#include <XmlRpcException.h>

#include <Eigen/Dense>
Expand Down Expand Up @@ -414,25 +417,35 @@ bool xmlParamToProp<RTT::PropertyBag>(const XmlRpc::XmlRpcValue &xml_value, RTT:
//! Convert an XmlRpc structure value into an abstract RTT PropertyBase
bool xmlParamToProp( const XmlRpc::XmlRpcValue &xml_value, RTT::base::PropertyBase* prop_base);

//! Convert an XmlRpc value to type T
template <class T> void xmlParamToValue(const XmlRpc::XmlRpcValue &xml_value, T &value) {
value = static_cast<const T&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value));
}

template <> void xmlParamToValue<float>(const XmlRpc::XmlRpcValue &xml_value, float &value) {
value = static_cast<const double&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value));
}

template <> void xmlParamToValue<unsigned int>(const XmlRpc::XmlRpcValue &xml_value, unsigned int &value) {
value = static_cast<const int&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value));
}
template <class XMLRPCType,class PropertyType, class enabled=void> struct XmlParamToValue{
static bool assign(const XMLRPCType& xml_value, PropertyType &prop_value)
{
return false;
}
};

template <> void xmlParamToValue<char>(const XmlRpc::XmlRpcValue &xml_value, char &value) {
value = static_cast<const int&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value));
}
template <class XMLRPCType, class PropertyType >
struct XmlParamToValue <XMLRPCType, PropertyType, typename boost::enable_if<boost::is_convertible<XMLRPCType,PropertyType> >::type >{
static bool assign(const XMLRPCType& xml_value, PropertyType &prop_value)
{
prop_value = xml_value;
return true;
}
};

template <> void xmlParamToValue<unsigned char>(const XmlRpc::XmlRpcValue &xml_value, unsigned char &value) {
value = static_cast<const int&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value));
//! Convert an XmlRpc value to type T
template <class PropertyType> bool xmlParamToValue(const XmlRpc::XmlRpcValue &xml_value, PropertyType &value) {
switch(xml_value.getType()) {
case XmlRpc::XmlRpcValue::TypeString:
return XmlParamToValue<std::string, PropertyType>::assign(static_cast<const std::string&>(const_cast<XmlRpc::XmlRpcValue &>(xml_value)),value);
case XmlRpc::XmlRpcValue::TypeDouble:
return XmlParamToValue<double, PropertyType>::assign(static_cast<double>(const_cast<XmlRpc::XmlRpcValue &>(xml_value)),value);
case XmlRpc::XmlRpcValue::TypeInt:
return XmlParamToValue<int, PropertyType>::assign(static_cast<int>(const_cast<XmlRpc::XmlRpcValue &>(xml_value)),value);
case XmlRpc::XmlRpcValue::TypeBoolean:
return XmlParamToValue<bool, PropertyType>::assign(static_cast<bool>(const_cast<XmlRpc::XmlRpcValue &>(xml_value)),value);
}
return false;
}

template <class T>
Expand All @@ -446,9 +459,8 @@ bool xmlParamToProp(
}

// Set the value
xmlParamToValue(xml_value, prop->set());
return xmlParamToValue(xml_value, prop->set());

return true;
}

template <class T>
Expand All @@ -469,11 +481,12 @@ bool xmlParamToProp(
// Copy the data into the vector property
std::vector<T> &vec = prop->value();
vec.resize(xml_value.size());
bool result = true;
for(size_t i=0; i<vec.size(); i++) {
xmlParamToValue(xml_value[i], vec[i]);
result &= xmlParamToValue(xml_value[i], vec[i]);
}

return true;
return result;
}

template <>
Expand All @@ -494,13 +507,14 @@ bool xmlParamToProp<bool>(
// Copy the data into the vector property
std::vector<bool> &vec = prop->value();
vec.resize(xml_value.size());
bool result = true;
for(size_t i=0; i<vec.size(); i++) {
bool temp;
xmlParamToValue(xml_value[i], temp);
result &= xmlParamToValue(xml_value[i], temp);
vec[i] = temp;
}

return true;
return result;
}

template <>
Expand All @@ -521,13 +535,14 @@ bool xmlParamToProp(
// Copy the data into the vector property
Eigen::VectorXd &vec = prop->value();
vec.resize(xml_value.size());
bool result = true;
for(size_t i=0; i<vec.size(); i++) {
double temp;
xmlParamToValue(xml_value[i], temp);
result &= xmlParamToValue(xml_value[i], temp);
vec[i] = temp;
}

return true;
return result;
}

template <>
Expand All @@ -548,13 +563,14 @@ bool xmlParamToProp(
// Copy the data into the vector property
Eigen::VectorXf &vec = prop->value();
vec.resize(xml_value.size());
bool result = true;
for(size_t i=0; i<vec.size(); i++) {
double temp;
xmlParamToValue(xml_value[i], temp);
result &= xmlParamToValue(xml_value[i], temp);
vec[i] = temp;
}

return true;
return result;
}

template <>
Expand Down Expand Up @@ -606,6 +622,8 @@ bool xmlParamToProp(
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<float>*>(prop_base));
case XmlRpc::XmlRpcValue::TypeInt:
return
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<double>*>(prop_base)) ||
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<float>*>(prop_base)) ||
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<int>*>(prop_base)) ||
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<unsigned int>*>(prop_base)) ||
xmlParamToProp(xml_value, dynamic_cast<RTT::Property<char>*>(prop_base)) ||
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ TEST_F(DynamicReconfigureTest, ConfigDescription)
EXPECT_EQ(5.0, *(tc.properties()->getPropertyType<double>("non_existent")));

// get a pointer to the reconfigure service
boost::shared_ptr<Server<TestConfig> > server = boost::shared_dynamic_cast<Server<TestConfig> >(tc.provides("test_reconfigure"));
boost::shared_ptr<Server<TestConfig> > server = boost::dynamic_pointer_cast<Server<TestConfig> >(tc.provides("test_reconfigure"));
ASSERT_TRUE(server.get());

// check ConfigDescription groups
Expand Down Expand Up @@ -191,7 +191,7 @@ TEST_F(DynamicReconfigureTest, AutoConfig)
ASSERT_TRUE(tc.provides()->hasService("reconfigure"));

// get a pointer to the reconfigure service
boost::shared_ptr<Server<AutoConfig> > server = boost::shared_dynamic_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
boost::shared_ptr<Server<AutoConfig> > server = boost::dynamic_pointer_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
ASSERT_TRUE(server.get());

// min/max/default property bag should exist with the same number of properties
Expand Down Expand Up @@ -287,7 +287,7 @@ TEST_F(DynamicReconfigureTest, AutoConfigAddPropertiesAndRefresh)
ASSERT_TRUE(tc.provides()->hasService("reconfigure"));

// get a pointer to the reconfigure service
boost::shared_ptr<Server<AutoConfig> > server = boost::shared_dynamic_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
boost::shared_ptr<Server<AutoConfig> > server = boost::dynamic_pointer_cast<Server<AutoConfig> >(tc.provides("reconfigure"));
ASSERT_TRUE(server.get());

// add a property to the TaskContext after having loaded the reconfigure service
Expand Down
1 change: 0 additions & 1 deletion typekits/rtt_actionlib_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

</description>
<maintainer email="[email protected]">Orocos Developers</maintainer>
<author>create_rtt_msgs</author>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
1 change: 0 additions & 1 deletion typekits/rtt_diagnostic_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

</description>
<maintainer email="[email protected]">Orocos Developers</maintainer>
<author>create_rtt_msgs</author>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
1 change: 0 additions & 1 deletion typekits/rtt_geometry_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

</description>
<maintainer email="[email protected]">Orocos Developers</maintainer>
<author>create_rtt_msgs</author>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
7 changes: 2 additions & 5 deletions typekits/rtt_kdl_conversions/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,9 @@
This package contains the components of the kdl_conversions package
</description>
<license>GPL</license>

<maintainer email="[email protected]">ruben smits</maintainer>
<maintainer email="[email protected]">Orocos Developers</maintainer>

<license>gpl</license>

<author>ruben smits</author>
<author>Ruben Smits</author>

<buildtool_depend>catkin</buildtool_depend>

Expand Down
Loading

0 comments on commit 1f54dca

Please sign in to comment.