30 #include "geometry_msgs/Twist.h" 31 #include "nav_msgs/Odometry.h" 32 #include "segway_rmp/SegwayStatusStamped.h" 36 #include <boost/thread.hpp> 107 }
catch (std::exception& e) {
108 std::string e_msg(e.what());
109 ROS_ERROR(
"Exception while connecting to the SegwayRMP, check your cables and power buttons.");
110 ROS_ERROR(
" %s", e_msg.c_str());
114 ROS_WARN(
"Not connected to the SegwayRMP, will retry in 5 seconds...");
144 boost::mutex::scoped_lock lock(this->
m_mutex);
154 }
else if (this->
linear_vel > this->target_linear_vel) {
171 }
else if (this->
angular_vel > this->target_angular_vel) {
180 ROS_DEBUG(
"Sending move command: linear velocity = %f, angular velocity = %f",
188 }
catch (std::exception& e) {
189 std::string e_msg(e.what());
190 ROS_ERROR(
"Error commanding Segway RMP: %s", e_msg.c_str());
203 this->
sss_msg.header.stamp = current_time;
220 ROS_INFO(
"Integrators reset by Segway RMP successfully");
227 ROS_INFO(
"Integrator reset by Segway RMP failed. Performing software reset");
242 this->
sss_msg.segway.left_wheel_displacement =
244 this->
sss_msg.segway.right_wheel_displacement =
246 this->
sss_msg.segway.forward_displacement =
248 this->
sss_msg.segway.yaw_displacement =
263 float forward_displacement =
266 float yaw_displacement =
276 float delta_forward_displacement =
278 double delta_time = (current_time-this->
last_time).toSec();
282 float delta_odometry_x =
283 delta_forward_displacement * std::cos(this->
odometry_w);
284 vel_x = delta_odometry_x / delta_time;
286 float delta_odometry_y =
287 delta_forward_displacement * std::sin(this->
odometry_w);
288 vel_y = delta_odometry_y / delta_time;
299 geometry_msgs::Quaternion quat =
308 this->
odom_trans.transform.translation.z = 0.0;
316 this->
odom_msg.header.stamp = current_time;
319 this->
odom_msg.pose.pose.position.z = 0.0;
320 this->
odom_msg.pose.pose.orientation = quat;
321 this->
odom_msg.pose.covariance[0] = 0.00001;
322 this->
odom_msg.pose.covariance[7] = 0.00001;
323 this->
odom_msg.pose.covariance[14] = 1000000000000.0;
324 this->
odom_msg.pose.covariance[21] = 1000000000000.0;
325 this->
odom_msg.pose.covariance[28] = 1000000000000.0;
326 this->
odom_msg.pose.covariance[35] = 0.001;
328 this->
odom_msg.twist.twist.linear.x = vel_x;
329 this->
odom_msg.twist.twist.linear.y = vel_y;
330 this->
odom_msg.twist.twist.angular.z = yaw_rate;
341 boost::mutex::scoped_lock lock(
m_mutex);
353 boost::mutex::scoped_lock lock(
m_mutex);
354 double x = msg->linear.x,
z = msg->angular.z;
396 std::stringstream ss;
397 ss <<
"Connecting to Segway RMP via ";
400 ss <<
"serial on serial port: " << this->
serial_port;
405 ss <<
"identified by the device serial number: " << this->
serial_number;
409 ss <<
"identified by the device description: " << this->
usb_description;
413 ss <<
"identified by the device index: " << this->
usb_index;
420 segwayrmp_node_instance =
this;
444 ROS_WARN(
"The serial_number parameter is set to the default 00000000, which shouldn't work.");
450 "Invalid USB selector: %s, valid types are 'index', 'serial_number', and 'description'.",
456 "Invalid interface type: %s, valid interface types are 'serial' and 'usb'.",
476 std::string segway_rmp_type_str;
477 n->
param(
"rmp_type", segway_rmp_type_str, std::string(
"200/400"));
478 if (segway_rmp_type_str ==
"200/400") {
480 }
else if (segway_rmp_type_str ==
"50/100") {
484 "Invalid rmp type: %s, valid rmp types are '200/400' and '50/100'.",
485 segway_rmp_type_str.c_str());
499 ROS_ERROR(
"Invalid linear positive acceleration limit of %f (must be non-negative).",
504 ROS_ERROR(
"Invalid linear negative acceleration limit of %f (must be non-negative).",
509 ROS_ERROR(
"Invalid angular positive acceleration limit of %f (must be non-negative).",
514 ROS_ERROR(
"Invalid angular negative acceleration limit of %f (must be non-negative).",
519 ROS_INFO(
"Accel limits: linear: pos = %f, neg = %f, angular: pos = %f, neg = %f.",
528 ROS_ERROR(
"Invalid max linear velocity limit of %f (must be non-negative).",
534 ROS_ERROR(
"Invalid max angular velocity limit of %f (must be non-negative).",
539 ROS_INFO(
"Velocity limits: linear: %f, angular: %f.",
644 int main(
int argc,
char **argv) {
645 ros::init(argc, argv,
"segway_rmp_node");
649 segwayrmp_node.
run();
tf::TransformBroadcaster odom_broadcaster
double segway_motor_timeout
void configureUSBByIndex(int device_index, int baudrate=460800)
std::string serial_number
void setLogMsgCallback(std::string log_level, LogMsgCallback callback)
void publish(const boost::shared_ptr< M > &message) const
double target_angular_vel
void handleStatus(segwayrmp::SegwayStatus::Ptr &ss_ptr)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
double angular_pos_accel_limit
void connect(bool reset_integrators=true)
segwayrmp::SegwayRMP * segway_rmp
segway_rmp::SegwayStatusStamped sss_msg
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher segway_status_pub
double linear_neg_accel_limit
nav_msgs::Odometry odom_msg
ros::Timer keep_alive_timer
void handleDebugMessages(const std::string &msg)
double linear_pos_accel_limit
std::string interface_type_str
void setStatusCallback(SegwayStatusCallback callback)
ControllerGainSchedule controller_gain_schedule
ros::Subscriber cmd_velSubscriber
float integrated_left_wheel_position
float powerbase_battery_voltage
double initial_integrated_right_wheel_position
void configureSerial(std::string port, int baudrate=460800)
geometry_msgs::TransformStamped odom_trans
std::string odom_frame_id
void move(float linear_velocity, float angular_velocity)
void handleErrorMessages(const std::string &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
float last_yaw_displacement
TFSIMD_FORCE_INLINE const tfScalar & x() const
void handleInfoMessages(const std::string &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double angular_neg_accel_limit
static SegwayRMPNode * segwayrmp_node_instance
void configureUSBByDescription(std::string description, int baudrate=460800)
segwayrmp::SegwayRMPType segway_rmp_type
double initial_integrated_forward_position
void configureUSBBySerial(std::string serial_number, int baudrate=460800)
std::string usb_description
TFSIMD_FORCE_INLINE const tfScalar & z() const
double initial_integrated_turn_position
float integrated_right_wheel_position
static double degrees_to_radians
float last_forward_displacement
void cmd_velCallback(const geometry_msgs::Twist::ConstPtr &msg)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Timer motor_timeout_timer
double initial_integrated_left_wheel_position
segwayrmp::InterfaceType interface_type
ros::Time odometry_reset_start_time
double odometry_reset_duration
OperationalMode operational_mode
float integrated_turn_position
double angular_odom_scale
float integrated_forward_position
static double radians_to_degrees
void motor_timeoutCallback(const ros::TimerEvent &e)
void keepAliveCallback(const ros::TimerEvent &e)
void handleStatusWrapper(segwayrmp::SegwayStatus::Ptr &ss)