Go to the documentation of this file.
20 #include <geometry_msgs/Twist.h>
21 #include <geometry_msgs/TwistStamped.h>
22 #include <sensor_msgs/Joy.h>
24 #include <boost/thread/mutex.hpp>
41 ROS_WARN(
"No 'root_frame' specified. Setting to 'base_link'!");
50 ROS_ERROR(
"No 'chain_tip_link' specified. Using 'root_frame' instead!");
71 boost::mutex::scoped_lock lock(
mutex_);
82 geometry_msgs::TwistStamped ts;
103 boost::mutex::scoped_lock lock(
mutex_);
115 boost::mutex::scoped_lock lock(
mutex_);
137 geometry_msgs::TwistStamped
ts_;
141 int main(
int argc,
char **argv)
143 ros::init(argc, argv,
"spacenav_commander");
ros::Subscriber twist_spacenav_sub_
void twistSpacenavCallback(const geometry_msgs::Twist::ConstPtr &msg)
Receive Twist from a 6d input device (e.g. 3DConnexion SpaceNavigator)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
void timerCallback(const ros::TimerEvent &)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
ros::Subscriber joy_spacenav_sub_
void joySpacenavCallback(const sensor_msgs::Joy::ConstPtr &msg)
Receive Joy from a 6d input device (e.g. 3DConnexion SpaceNavigator)
bool hasParam(const std::string &key) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
geometry_msgs::TwistStamped ts_
ros::Publisher twist_pub_
T param(const std::string ¶m_name, const T &default_val) const
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)