Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support Boolean variables #403

Open
wants to merge 2 commits into
base: melodic-devel
Choose a base branch
from
Open
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
2 changes: 2 additions & 0 deletions canopen_chain_node/src/ros_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <socketcan_interface/xmlrpc_settings.h>
#include <canopen_chain_node/ros_chain.h>

#include <std_msgs/Bool.h>
#include <std_msgs/Int8.h>
#include <std_msgs/Int16.h>
#include <std_msgs/Int32.h>
Expand Down Expand Up @@ -41,6 +42,7 @@ PublishFuncType createPublishFunc(ros::NodeHandle &nh, const std::string &name,
ObjectStorageSharedPtr s = node->getStorage();

switch(ObjectDict::DataTypes(s->dict_->get(key)->data_type)){
case ObjectDict::DEFTYPE_BOOLEAN: return create< std_msgs::Bool, ObjectDict::DEFTYPE_BOOLEAN >(nh, name, s, key, force);
case ObjectDict::DEFTYPE_INTEGER8: return create< std_msgs::Int8, ObjectDict::DEFTYPE_INTEGER8 >(nh, name, s, key, force);
case ObjectDict::DEFTYPE_INTEGER16: return create< std_msgs::Int16, ObjectDict::DEFTYPE_INTEGER16 >(nh, name, s, key, force);
case ObjectDict::DEFTYPE_INTEGER32: return create< std_msgs::Int32, ObjectDict::DEFTYPE_INTEGER32 >(nh, name, s, key, force);
Expand Down
3 changes: 3 additions & 0 deletions canopen_master/include/canopen_master/objdict.h
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,7 @@ class ObjectDict{
RECORD = 0x09
};
enum DataTypes{
DEFTYPE_BOOLEAN = 0x0001,
DEFTYPE_INTEGER8 = 0x0002,
DEFTYPE_INTEGER16 = 0x0003,
DEFTYPE_INTEGER32 = 0x0004,
Expand Down Expand Up @@ -539,6 +540,7 @@ typedef ObjectStorage::ObjectStorageSharedPtr ObjectStorageSharedPtr;
template<> String & ObjectStorage::Data::access();
template<> String & ObjectStorage::Data::allocate();

template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_BOOLEAN> { typedef bool type; };
template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER8> { typedef int8_t type;};
template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER16> { typedef int16_t type;};
template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_INTEGER32> { typedef int32_t type;};
Expand All @@ -559,6 +561,7 @@ template<> struct ObjectStorage::DataType<ObjectDict::DEFTYPE_DOMAIN> { typedef

template<typename T, typename R> static R *branch_type(const uint16_t data_type){
switch(ObjectDict::DataTypes(data_type)){
case ObjectDict::DEFTYPE_BOOLEAN: return T::template func< ObjectDict::DEFTYPE_BOOLEAN >;
case ObjectDict::DEFTYPE_INTEGER8: return T::template func< ObjectDict::DEFTYPE_INTEGER8 >;
case ObjectDict::DEFTYPE_INTEGER16: return T::template func< ObjectDict::DEFTYPE_INTEGER16 >;
case ObjectDict::DEFTYPE_INTEGER32: return T::template func< ObjectDict::DEFTYPE_INTEGER32 >;
Expand Down
5 changes: 5 additions & 0 deletions canopen_master/src/objdict.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,10 @@ void set_access( ObjectDict::Entry &entry, std::string access){

template<typename T> T int_from_string(const std::string &s);

template<> bool int_from_string(const std::string &s){
return strtol(s.c_str(), 0, 0 ) > 0;
}

template<> int8_t int_from_string(const std::string &s){
return strtol(s.c_str(), 0, 0);
}
Expand Down Expand Up @@ -165,6 +169,7 @@ struct ReadAnyValue{
return branch_type<ReadAnyValue, HoldAny (boost::property_tree::iptree &, const std::string &)>(data_type)(pt, key);
}
};
template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_BOOLEAN>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<bool>(pt, key); }
template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER8>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int8_t>(pt,key); }
template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER16>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int16_t>(pt,key); }
template<> HoldAny ReadAnyValue::func<ObjectDict::DEFTYPE_INTEGER32>(boost::property_tree::iptree &pt, const std::string &key){ return parse_int<int32_t>(pt,key); }
Expand Down