File tree Expand file tree Collapse file tree 1 file changed +7
-3
lines changed
rm_common/include/rm_common/decision Expand file tree Collapse file tree 1 file changed +7
-3
lines changed Original file line number Diff line number Diff line change @@ -893,12 +893,16 @@ class CameraSwitchCommandSender : public CommandSenderBase<std_msgs::String>
893893public:
894894 explicit CameraSwitchCommandSender (ros::NodeHandle& nh) : CommandSenderBase<std_msgs::String>(nh)
895895 {
896- ROS_ASSERT (nh.getParam (" camera1_name" , camera1_name_) && nh.getParam (" camera2_name" , camera2_name_));
896+ ROS_ASSERT (nh.getParam (" camera_left_name" , camera1_name_) && nh.getParam (" camera_right_name" , camera2_name_));
897+ msg_.data = camera2_name_;
898+ }
899+ void switchCameraLeft ()
900+ {
897901 msg_.data = camera1_name_;
898902 }
899- void switchCamera ()
903+ void switchCameraRight ()
900904 {
901- msg_.data = msg_. data == camera1_name_ ? camera2_name_ : camera1_name_ ;
905+ msg_.data = camera2_name_;
902906 }
903907 void sendCommand (const ros::Time& time) override
904908 {
You can’t perform that action at this time.
0 commit comments