Subscriber Error.
I'm having next code developed in c++:
stdxros.hpp
#ifndef STDXROS_HPP
#define STDXROS_HPP
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float32.h>
#include <std_msgs/Float64.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/LaserScan.h>
#include <nav_msgs/Odometry.h>
#include <rosaria/BumperState.h>
#include <laser_assembler/AssembleScans.h>
#endif
//GeneralController.h
#include "stdxros.hpp"
class GeneralController
{
private:
ros::NodeHandle nh;
public:
GeneralController(ros::NodeHandle nh_);
~GeneralController(void);
private:
public:
void batteryStateCallback(const std_msgs::Float32:ConstPtr& battery);
void bumperStateCallback(const rosaria::BumperState::ConstPtr& bumpers);
void poseStateCallback(const nav_msgs::Odometry::ConstPtr& pose);
};
//GeneralController.cpp
#include "GeneralController.h"
GeneralController::GeneralController(ros::NodeHandle nh_)
{
this->nh = nh_;
}
void GeneralController::bumperStateCallback(const rosaria::BumperState::ConstPtr& bumpers){
std::cout << "Bumper Event Thrown" << std::endl;
}
void GeneralController::poseStateCallback(const nav_msgs::Odometry::ConstPtr& pose){
std::cout << "Pose Event Thrown" << std::endl;
}
void GeneralController::batteryStateCallback(const std_msgs::Float32::ConstPtr& battery){
std::cout << "Battery Event Thrown" << std::endl;
}
servidor.cpp
#include <signal.h>
#include "GeneralController.h"
GeneralController *robot;
int main(int argc, char** argv){
ros::init(argc, argv, "bea_con_suerte");
ros::start();
ros::NodeHandle nh;
robot = new GeneralController(nh);
ros::Subscriber bumper_state = nh.subscribe("/RosAria/bumper_state", 1, &GeneralController::bumperStateCallback, robot);
while(continue_execution){
}
return 0;
}
Makefile
IDIR=/opt/ros/hydro/include
UDIR=/usr/include/libusb-1.0
LDIR=/opt/ros/hydro/lib -Wl,-rpath,/opt/ros/hydro/lib
LIBS=pkg-config --libs libusb-1.0
CC=g++ -std=c++11
CFLAGS=-I$(IDIR) -I$(UDIR)
LFLAGS=-L$(LDIR)
OPTIONS=-lusb-1.0 -lroscpp -lrosconsole -lrostime
AR=ar
all:
$(CC) GeneralController.cpp -o LuckyBea $(CFLAGS) $(LFLAGS) $(OPTIONS)
clean:
rm -rf *.o *.a* *~LuckyBea
when execute makefile, next errors are thrown:
g++ -std=c++11 GeneralController.cpp SocketNode2.cpp servidor.cpp SerialPort.cpp -o LuckyBea -I/opt/ros/hydro/include -I/usr/include/libusb-1.0 -L/opt/ros/hydro/lib -Wl,-rpath,/opt/ros/hydro/lib -lusb-1.0 -lroscpp -lrosconsole -lrostime
In file included from /opt/ros/hydro/include/ros/subscriber.h:33:0,
from /opt/ros/hydro/include/ros/node_handle.h:33,
from /opt/ros/hydro/include/ros/ros.h:45,
from stdxros.hpp:4,
from GeneralController.h:8,
from servidor.cpp:2:
/opt/ros/hydro/include/ros/subscription_callback_helper.h: In instantiation of ‘void ros::SubscriptionCallbackHelperT<P, Enabled>::call(ros::SubscriptionCallbackHelperCallParams&) [with P = const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&; Enabled = void]’:
servidor.cpp:50:1: required from here
/opt/ros/hydro/include/ros/subscription_callback_helper.h:140:5: error: use of deleted function ‘boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >::shared_ptr(const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&)’
callback_(ParameterAdapter<P>::getParameter(event));
^
In file included from /usr/include/boost/shared_ptr.hpp:17:0,
from /usr/include/boost/format/alt_sstream.hpp:21,
from /usr/include/boost/format/internals.hpp:23,
from /usr/include/boost/format.hpp:38,
from /usr/include/boost/math/policies/error_handling.hpp:30,
from /usr/include/boost/math/special_functions/round.hpp:14,
from /opt/ros/hydro/include/ros/time.h:58,
from /opt/ros/hydro/include/ros/ros.h:38,
from stdxros.hpp:4,
from GeneralController.h:8,
from servidor.cpp:2:
/usr/include/boost/smart_ptr/shared_ptr.hpp:168:25: note: ‘boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >::shared_ptr(const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&)’ is implicitly declared as deleted because ‘boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >’ declares a move constructor or move assignment operator
template<class T> class shared_ptr
^
In file included from /usr/include/boost/config.hpp:57:0,
from /usr/include/boost/cstdint.hpp:36,
from /usr/include/boost/math/tools/config.hpp:13,
from /usr/include/boost/math/special_functions/round.hpp:13,
from /opt/ros/hydro/include/ros/time.h:58,
from /opt/ros/hydro/include/ros/ros.h:38,
from stdxros.hpp:4,
from GeneralController.h:8,
from servidor.cpp:2:
/usr/include/boost/function/function_template.hpp:1006:3: error: initializing argument 1 of ‘boost::function1<R, T1>::result_type boost::function1<R, T1>::operator()(T0) const [with R = void; T0 = boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >; boost::function1<R, T1>::result_type = void]’
BOOST_FUNCTION_FUNCTION<R BOOST_FUNCTION_COMMA BOOST_FUNCTION_TEMPLATE_ARGS>
^
In file included from /usr/include/boost/shared_ptr.hpp:17:0,
from /usr/include/boost/format/alt_sstream.hpp:21,
from /usr/include/boost/format/internals.hpp:23,
from /usr/include/boost/format.hpp:38,
from /usr/include/boost/math/policies/error_handling.hpp:30,
from /usr/include/boost/math/special_functions/round.hpp:14,
from /opt/ros/hydro/include/ros/time.h:58,
from /opt/ros/hydro/include/ros/ros.h:38,
from stdxros.hpp:4,
from GeneralController.h:8,
from servidor.cpp:2:
/usr/include/boost/smart_ptr/shared_ptr.hpp: In instantiation of ‘boost::shared_ptr<T>& boost::shared_ptr<T>::operator=(const boost::shared_ptr<T>&) [with T = rosaria::BumperState_<std::allocator<void> >]’:
/opt/ros/hydro/include/ros/subscription_callback_helper.h:127:27: required from ‘ros::VoidConstPtr ros::SubscriptionCallbackHelperT<P, Enabled>::deserialize(const ros::SubscriptionCallbackHelperDeserializeParams&) [with P = const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&; Enabled = void; ros::VoidConstPtr = boost::shared_ptr<const void>]’
servidor.cpp:50:1: required from here
/usr/include/boost/smart_ptr/shared_ptr.hpp:305:9: error: use of deleted function ‘boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >::shared_ptr(const boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >&)’
this_type(r).swap(*this);
^
/usr/include/boost/smart_ptr/shared_ptr.hpp:168:25: note: ‘boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >::shared_ptr(const boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >&)’ is implicitly declared as deleted because ‘boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >’ declares a move constructor or move assignment operator
template<class T> class shared_ptr
^
/usr/include/boost/smart_ptr/shared_ptr.hpp: In instantiation of ‘boost::shared_ptr<T>& boost::shared_ptr<T>::operator=(const boost::shared_ptr<T>&) [with T = std::map<std::basic_string<char>, std::basic_string<char> >]’:
/opt/ros/hydro/include/ros/subscription_callback_helper.h:128:37: required from ‘ros::VoidConstPtr ros::SubscriptionCallbackHelperT<P, Enabled>::deserialize(const ros::SubscriptionCallbackHelperDeserializeParams&) [with P = const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&; Enabled = void; ros::VoidConstPtr = boost::shared_ptr<const void>]’
servidor.cpp:50:1: required from here
/usr/include/boost/smart_ptr/shared_ptr.hpp:305:9: error: use of deleted function ‘boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >::shared_ptr(const boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >&)’
this_type(r).swap(*this);
^
/usr/include/boost/smart_ptr/shared_ptr.hpp:168:25: note: ‘boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >::shared_ptr(const boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >&)’ is implicitly declared as deleted because ‘boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >’ declares a move constructor or move assignment operator
template<class T> class shared_ptr
^
/usr/include/boost/smart_ptr/shared_ptr.hpp: In instantiation of ‘boost::shared_ptr<T>& boost::shared_ptr<T>::operator=(const boost::shared_ptr<T>&) [with T = const rosaria::BumperState_<std::allocator<void> >]’:
/opt/ros/hydro/include/ros/message_event.h:134:14: required from ‘void ros::MessageEvent<M>::init(const ConstMessagePtr&, const boost::shared_ptr<std::map<std::basic_string<char>, std::basic_string<char> > >&, ros::Time, bool, const CreateFunction&) [with M = const rosaria::BumperState_<std::allocator<void> >; ros::MessageEvent<M>::ConstMessagePtr = boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >; typename boost::add_const<M>::type = const rosaria::BumperState_<std::allocator<void> >; ros::MessageEvent<M>::CreateFunction = boost::function<boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >()>; typename boost::remove_const<M>::type = rosaria::BumperState_<std::allocator<void> >]’
/opt/ros/hydro/include/ros/message_event.h:106:188: required from ‘ros::MessageEvent<M>::MessageEvent(const ros::MessageEvent<const void>&, const CreateFunction&) [with M = const rosaria::BumperState_<std::allocator<void> >; ros::MessageEvent<M>::CreateFunction = boost::function<boost::shared_ptr<rosaria::BumperState_<std::allocator<void> > >()>; typename boost::remove_const<M>::type = rosaria::BumperState_<std::allocator<void> >]’
/opt/ros/hydro/include/ros/subscription_callback_helper.h:139:38: required from ‘void ros::SubscriptionCallbackHelperT<P, Enabled>::call(ros::SubscriptionCallbackHelperCallParams&) [with P = const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&; Enabled = void]’
servidor.cpp:50:1: required from here
/usr/include/boost/smart_ptr/shared_ptr.hpp:305:9: error: use of deleted function ‘boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >::shared_ptr(const boost::shared_ptr<const rosaria::BumperState_<std::allocator<void> > >&)’
this_type(r).swap(*this);
^
make: *** [all] Error 1
Can you help me please?
Asked by bielpiero on 2014-12-15 08:23:21 UTC
Comments