Skip to content

Commit

Permalink
Adjust EOF position and remove unnecessary whitespace
Browse files Browse the repository at this point in the history
  • Loading branch information
sunghowoo committed Oct 29, 2024
1 parent 1a76088 commit d57a888
Show file tree
Hide file tree
Showing 16 changed files with 41 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,13 +21,13 @@

Turtlebot3ManipulationBringup::Turtlebot3ManipulationBringup()
: nh_(""),
arm_action_server_(nh_,
"arm_controller/follow_joint_trajectory",
boost::bind(&Turtlebot3ManipulationBringup::armActionCallback, this, _1),
arm_action_server_(nh_,
"arm_controller/follow_joint_trajectory",
boost::bind(&Turtlebot3ManipulationBringup::armActionCallback, this, _1),
false),
gripper_action_server_(nh_,
"gripper_controller/follow_joint_trajectory",
boost::bind(&Turtlebot3ManipulationBringup::gripperActionCallback, this, _1),
gripper_action_server_(nh_,
"gripper_controller/follow_joint_trajectory",
boost::bind(&Turtlebot3ManipulationBringup::gripperActionCallback, this, _1),
false)
{
// Init Publisher
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@
<!-- send robot urdf to param server -->
<include file="$(find turtlebot3_manipulation_description)/launch/turtlebot3_manipulation_upload.launch">
<arg name="model" value="$(arg model)"/>
</include>
</include>

<!-- start joint state publisher -->
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
<param name="/use_gui" value="$(arg use_gui)"/>
<rosparam param="source_list">["/joint_states"]</rosparam>
</node>

<!-- start robot state publisher -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,5 +46,5 @@

<!-- Transmission 6 -->
<xacro:SimpleTransmissionEffort n="6" joint="gripper_sub" />

</robot>
6 changes: 3 additions & 3 deletions turtlebot3_manipulation_gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,9 @@ catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS
geometry_msgs
roscpp
std_msgs
sensor_msgs
roscpp
std_msgs
sensor_msgs
moveit_msgs
moveit_core
moveit_ros_planning
Expand Down
2 changes: 1 addition & 1 deletion turtlebot3_manipulation_gui/src/main_window.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ using namespace Qt;
*****************************************************************************/

MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
: QMainWindow(parent),
: QMainWindow(parent),
qnode(argc,argv)
{
ui.setupUi(this); // Calling this incidentally connects all ui's triggers to on_...() callbacks in this class.
Expand Down
26 changes: 13 additions & 13 deletions turtlebot3_manipulation_gui/src/qnode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,14 @@ namespace turtlebot3_manipulation_gui {
** Implementation
*****************************************************************************/

QNode::QNode(int argc, char** argv)
QNode::QNode(int argc, char** argv)
:init_argc(argc),
init_argv(argv)
{}

QNode::~QNode()
{
if(ros::isStarted())
if(ros::isStarted())
{
ros::shutdown(); // explicitly needed since we use ros::start();
ros::waitForShutdown();
Expand All @@ -55,15 +55,15 @@ QNode::~QNode()
bool QNode::init()
{
ros::init(init_argc,init_argv,"turtlebot3_manipulation_gui");
if ( ! ros::master::check() )
if ( ! ros::master::check() )
{
return false;
}
ros::start(); // explicitly needed since our nodehandle is going out of scope.
ros::NodeHandle n("");

// Moveit
ros::AsyncSpinner spinner(1);
// Moveit
ros::AsyncSpinner spinner(1);
spinner.start();

// Move group arm
Expand Down Expand Up @@ -93,7 +93,7 @@ void QNode::run()

void QNode::updateRobotState()
{
ros::AsyncSpinner spinner(1);
ros::AsyncSpinner spinner(1);
spinner.start();

std::vector<double> jointValues = move_group_->getCurrentJointValues();
Expand All @@ -106,7 +106,7 @@ void QNode::updateRobotState()
temp_angle.push_back(jointValues2.at(0));
present_joint_angle_ = temp_angle;

geometry_msgs::Pose current_pose = move_group_->getCurrentPose().pose;
geometry_msgs::Pose current_pose = move_group_->getCurrentPose().pose;
std::vector<double> temp_position;
temp_position.push_back(current_pose.position.x);
temp_position.push_back(current_pose.position.y);
Expand All @@ -126,13 +126,13 @@ std::vector<double> QNode::getPresentKinematicsPosition()

bool QNode::setJointSpacePath(std::vector<double> joint_angle, double path_time)
{
ros::AsyncSpinner spinner(1);
ros::AsyncSpinner spinner(1);
spinner.start();

// Next get the current set of joint values for the group.
const robot_state::JointModelGroup* joint_model_group =
move_group_->getCurrentState()->getJointModelGroup("arm");

moveit::core::RobotStatePtr current_state = move_group_->getCurrentState();

std::vector<double> joint_group_positions;
Expand All @@ -158,7 +158,7 @@ bool QNode::setJointSpacePath(std::vector<double> joint_angle, double path_time)

bool QNode::setTaskSpacePath(std::vector<double> kinematics_pose, double path_time)
{
ros::AsyncSpinner spinner(1);
ros::AsyncSpinner spinner(1);
spinner.start();

// Uncomment below to keep the end-effector parallel to the ground
Expand Down Expand Up @@ -199,13 +199,13 @@ bool QNode::setTaskSpacePath(std::vector<double> kinematics_pose, double path_ti

bool QNode::setToolControl(std::vector<double> joint_angle)
{
ros::AsyncSpinner spinner(1);
ros::AsyncSpinner spinner(1);
spinner.start();

// Next get the current set of joint values for the group.
const robot_state::JointModelGroup* joint_model_group =
move_group2_->getCurrentState()->getJointModelGroup("gripper");

moveit::core::RobotStatePtr current_state = move_group2_->getCurrentState();

std::vector<double> joint_group_positions;
Expand All @@ -223,6 +223,6 @@ bool QNode::setToolControl(std::vector<double> joint_angle)
move_group2_->move();

spinner.stop();
return true;
return true;
}
} // namespace turtlebot3_manipulation_gui
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,4 @@ collision_clearence: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
max_recovery_attempts: 5
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,4 @@ controller_list:
- joint4
- name: fake_gripper_controller
joints:
- gripper
- gripper
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,4 @@ joint_limits:
has_velocity_limits: true
max_velocity: 4.8
has_acceleration_limits: false
max_acceleration: 0
max_acceleration: 0
Original file line number Diff line number Diff line change
Expand Up @@ -175,4 +175,4 @@ gripper:
- SPARS
- SPARStwo
projection_evaluator: joints(gripper,gripper_sub)
longest_valid_segment_fraction: 0.005
longest_valid_segment_fraction: 0.005
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it
sensors:
- {}
- {}
2 changes: 1 addition & 1 deletion turtlebot3_manipulation_moveit_config/launch/demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
</include>

<!-- If needed, broadcast static tf for robot root -->


<!-- We do not have a robot connected, so publish fake joint states -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
</include>

<!-- If needed, broadcast static tf for robot root -->


<!-- We do not have a robot connected, so publish fake joint states -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
Expand All @@ -54,7 +54,7 @@
<arg name="fake_execution" value="false"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
</include>
</include>

<!-- Run Rviz and load the default config to see the state of the move_group node -->
<include file="$(find turtlebot3_manipulation_moveit_config)/launch/moveit_rviz.launch">
Expand Down
4 changes: 2 additions & 2 deletions turtlebot3_manipulation_navigation/launch/navigation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter" output="screen" >
<rosparam command="load" file="$(find turtlebot3_manipulation_slam)/config/scan_data_filter.yaml" />
</node>
</node>

<!-- Map server -->
<node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)"/>
Expand All @@ -34,7 +34,7 @@
</include>

<!-- rviz -->
<group if="$(arg open_rviz)">
<group if="$(arg open_rviz)">
<node pkg="rviz" type="rviz" name="rviz" required="true"
args="-d $(find turtlebot3_manipulation_navigation)/rviz/turtlebot3_manipulation_navigation.rviz" output="screen"/>
</group>
Expand Down
2 changes: 1 addition & 1 deletion turtlebot3_manipulation_slam/config/scan_data_filter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@ scan_filter_chain:
type: laser_filters/LaserScanAngularBoundsFilterInPlace
params:
lower_angle: 2.0944
upper_angle: 4.18879
upper_angle: 4.18879
8 changes: 4 additions & 4 deletions turtlebot3_manipulation_slam/launch/slam.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
</node>

<!-- <group ns="$(arg use_robot_name)"> -->
<!-- Gmapping -->
<node pkg="laser_filters" type="scan_to_scan_filter_chain" name="laser_filter" output="screen" >
<rosparam command="load" file="$(find turtlebot3_manipulation_slam)/config/scan_data_filter.yaml" />
</node>

<node pkg="gmapping" type="slam_gmapping" name="turtlebot3_slam_gmapping" output="screen">
<!-- <remap from="scan" to="$(arg scan_topic)"/> -->

Expand Down Expand Up @@ -63,9 +63,9 @@
<!-- </group> -->

<!-- rviz -->
<group if="$(arg open_rviz)">
<group if="$(arg open_rviz)">
<node pkg="rviz" type="rviz" name="rviz" required="true"
args="-d $(find turtlebot3_manipulation_slam)/rviz/turtlebot3_manipulation_slam.rviz"/>
</group>

</launch>
</launch>

0 comments on commit d57a888

Please sign in to comment.