spacenav_commander.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <string>
19 #include <ros/ros.h>
20 #include <geometry_msgs/Twist.h>
21 #include <geometry_msgs/TwistStamped.h>
22 #include <sensor_msgs/Joy.h>
23 
24 #include <boost/thread/mutex.hpp>
25 
27 {
28 public:
30  {
33  twist_pub_ = nh_.advertise<geometry_msgs::TwistStamped> ("twist_controller/command_twist_stamped", 1);
34 
35  if (nh_.hasParam("root_frame"))
36  {
37  nh_.getParam("root_frame", root_frame_);
38  }
39  else
40  {
41  ROS_WARN("No 'root_frame' specified. Setting to 'base_link'!");
42  root_frame_ = "base_link";
43  }
44  if (nh_.hasParam("chain_tip_link"))
45  {
46  nh_.getParam("chain_tip_link", tip_frame_);
47  }
48  else
49  {
50  ROS_ERROR("No 'chain_tip_link' specified. Using 'root_frame' instead!");
52  }
53 
54  // could be made a parameter or even dynamically reconfigurable
55  ros::NodeHandle nh_priv("~");
56  nh_priv.param<double>("scaling_factor", scaling_factor_, 0.1);
57  dead_man_enabled_ = false;
59 
60  timer_ = nh_.createTimer(ros::Duration(0.01), &SpacenavCommander::timerCallback, this); // guarantee 100Hz
61  timer_.start();
62  }
63 
65  {
66  }
67 
69  void joySpacenavCallback(const sensor_msgs::Joy::ConstPtr& msg)
70  {
71  boost::mutex::scoped_lock lock(mutex_);
72 
73  if (msg->buttons[0]) // dead man
74  {
75  dead_man_enabled_ = true;
76  }
77  else
78  {
79  // publish one last zero-twist
81  {
82  geometry_msgs::TwistStamped ts;
83  ts.header.frame_id = root_frame_;
84  ts.header.stamp = ros::Time::now();
85  twist_pub_.publish(ts);
86  }
87  dead_man_enabled_ = false;
88  }
89 
90  if (msg->buttons[1]) // root_frame/tip_frame selection
91  {
93  }
94  else
95  {
97  }
98  }
99 
101  void twistSpacenavCallback(const geometry_msgs::Twist::ConstPtr& msg)
102  {
103  boost::mutex::scoped_lock lock(mutex_);
104 
105  ts_.twist.linear.x = scaling_factor_ * msg->linear.x;
106  ts_.twist.linear.y = scaling_factor_ * msg->linear.y;
107  ts_.twist.linear.z = scaling_factor_ * msg->linear.z;
108  ts_.twist.angular.x = scaling_factor_ * msg->angular.x;
109  ts_.twist.angular.y = scaling_factor_ * msg->angular.y;
110  ts_.twist.angular.z = scaling_factor_ * msg->angular.z;
111  }
112 
114  {
115  boost::mutex::scoped_lock lock(mutex_);
116 
117  if (dead_man_enabled_)
118  {
119  ts_.header.frame_id = frame_id_;
120  ts_.header.stamp = ros::Time::now();
121 
123  }
124  }
125 
126 private:
132 
134  boost::mutex mutex_;
137  geometry_msgs::TwistStamped ts_;
138 };
139 
140 
141 int main(int argc, char **argv)
142 {
143  ros::init(argc, argv, "spacenav_commander");
145  ros::spin();
146 }
void twistSpacenavCallback(const geometry_msgs::Twist::ConstPtr &msg)
Receive Twist from a 6d input device (e.g. 3DConnexion SpaceNavigator)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void start()
#define ROS_ERROR(...)
#define ROS_WARN(...)
void joySpacenavCallback(const sensor_msgs::Joy::ConstPtr &msg)
Receive Joy from a 6d input device (e.g. 3DConnexion SpaceNavigator)
void timerCallback(const ros::TimerEvent &)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
bool getParam(const std::string &key, std::string &s) const
ros::Subscriber joy_spacenav_sub_
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
bool hasParam(const std::string &key) const
ros::Publisher twist_pub_
geometry_msgs::TwistStamped ts_
static Time now()
ros::Subscriber twist_spacenav_sub_


cob_frame_tracker
Author(s): Felix Messmer
autogenerated on Mon May 1 2023 02:50:14